network.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.h"
33 
34 #include <functional>
35 #ifdef USE_GLOG
36 #include <glog/logging.h>
37 #else
38 #include <aditof/log.h>
39 #endif
42 #include <iostream>
43 
44 std::unique_ptr<zmq::socket_t> frame_socket;
45 std::unique_ptr<zmq::context_t> zmq_context;
47 
48 static std::atomic<bool> running{true};
49 
50 #define RX_BUFFER_BYTES (20996420)
51 #define MAX_RETRY_CNT 3
52 
54 
55 using namespace google::protobuf::io;
56 using namespace payload;
57 using namespace std;
58 
59 struct clientData {
61  std::vector<char> data;
62 };
63 
64 int nBytes = 0; /*no of bytes sent*/
65 int recv_data_error = 0; /*flag for recv data*/
66 char server_msg[] = "Connection Allowed";
67 
68 /*Declare static members*/
69 std::vector<std::unique_ptr<zmq::socket_t>> Network::command_socket;
70 std::vector<std::unique_ptr<zmq::socket_t>> Network::monitor_sockets;
71 std::vector<std::unique_ptr<zmq::context_t>> Network::contexts;
72 ClientRequest Network::send_buff[MAX_CAMERA_NUM];
73 ServerResponse Network::recv_buff[MAX_CAMERA_NUM];
74 recursive_mutex Network::m_mutex[MAX_CAMERA_NUM];
76 condition_variable_any Network::Cond_Var[MAX_CAMERA_NUM];
77 condition_variable Network::thread_Cond_Var[MAX_CAMERA_NUM];
78 static const int FRAME_PREPADDING_BYTES = 2;
79 
85 
87 std::vector<std::string> m_connectionList;
88 
89 /*
90 * isServer_Connected(): checks if server is connected
91 * Parameters: none
92 * returns: true - if server is connected
93  false - if no server is connected
94 * Desription: This function checks if server is connected and returns
95 Server_Connected flag value.
96 */
98  return Network::Server_Connected[m_connectionId];
99 }
100 
101 /*
102 * isThread_Running(): check if thread created is running
103 * Parameters: none
104 * returns: true - if thread is alive
105  false - if thread is not running
106 * Desription: This function returns Thread_Running flag value to check if
107 thread is running.
108 */
110  /*Return true if thread has completed*/
111  if (Network::Thread_Running[m_connectionId] == 2) {
112  return true;
113  } else {
114  return false;
115  }
116 }
117 
118 /*
119 * isData_Received(): check if data is sent to server and returns Send_Successful
120 flag value
121 * Parameters: none
122 * returns: true - if data has been sent succesfully
123  false - if error in data sending
124 * Desription: This function returns Send_Successful flag value
125 */
127  return Network::Send_Successful[m_connectionId];
128 }
129 
130 /*
131 * isData_Received(): check if data received from server and returns
132 Data_Received flag value
133 * Parameters: none
134 * returns: true - if data received successfully
135  false - if error in data receiving
136 * Desription: This function is used to check if any data received from server
137 * returns Data_Received flag value.
138 */
140  return Network::Data_Received[m_connectionId];
141 }
142 
143 /*
144 * ServerConnect(): intializes the zmq sockets and connects to server
145 * Parameters: ip - the ip address of the server to connect to
146 * returns: 0 - on success
147  -1 - on error
148 * Desription: This function initializes the zmq sockets and connects to server.
149 */
151 
152  uint8_t numTry = 0;
153  zmq_ip = ip;
154  // Set up ZeroMQ context and socket
155  std::unique_ptr<zmq::context_t> m_context;
156  std::unique_ptr<zmq::socket_t> m_command;
157  std::unique_ptr<zmq::socket_t> m_monitor;
158  m_context = std::make_unique<zmq::context_t>(2);
159  contexts.at(m_connectionId) = std::move(m_context);
160  m_command =
161  std::make_unique<zmq::socket_t>(*contexts.at(m_connectionId), ZMQ_REQ);
162  m_monitor =
163  std::make_unique<zmq::socket_t>(*contexts.at(m_connectionId), ZMQ_PAIR);
164 
165  if (!m_connectionId) {
166 
167  command_socket.clear();
168  command_socket.emplace_back(std::move(m_command));
169 
170  monitor_sockets.clear();
171  monitor_sockets.emplace_back(std::move(m_monitor));
172 
173  } else {
174 
175  for (size_t i = 0; i < command_socket.size(); i++) {
176  if (command_socket.at(i) == nullptr) {
177  command_socket.erase(command_socket.begin() + i);
178  i--;
179  }
180  }
181  command_socket.push_back(std::move(m_command));
182 
183  for (size_t i = 0; i < monitor_sockets.size(); i++) {
184  if (monitor_sockets.at(i) == nullptr) {
185  monitor_sockets.erase(monitor_sockets.begin() + i);
186  i--;
187  }
188  }
189  monitor_sockets.push_back(std::move(m_monitor));
190  }
191 
192  std::string monitor_endpoint =
193  "inproc://monitor-client" + std::to_string(m_connectionId);
194  zmq_socket_monitor(command_socket[m_connectionId]->handle(),
195  monitor_endpoint.c_str(), ZMQ_EVENT_ALL);
196 
197  // Connect the monitor socket
198  monitor_sockets[m_connectionId]->connect(monitor_endpoint);
199 
200  // Start a new thread to service any pending events on ZeroMQ socket
201  threadObj[m_connectionId] =
202  std::thread(&Network::call_zmq_service, this, std::ref(ip));
203 
204  Network::Thread_Detached[m_connectionId] = true;
205  threadObj[m_connectionId].detach();
206 
207  while (numTry < 3) { // Try 3 times to connect
208 
209  if (!Server_Connected[m_connectionId]) {
210  LOG(INFO) << "Attempting to connect server... ";
211  try {
212 
213  command_socket[m_connectionId]->connect("tcp://" + ip +
214  ":5556");
215  } catch (const zmq::error_t &e) {
216  LOG(ERROR) << "Error Connecting to server" << e.what();
217  if (e.num() == EHOSTUNREACH) {
218  LOG(ERROR) << "Host is unreachable";
219  }
220  }
221  }
222  numTry++;
223  }
224 
225  /*Wait for thread to be ready and server is connected*/
226 
227  std::unique_lock<std::recursive_mutex> mlock(m_mutex[m_connectionId]);
228 
229  /*Wait till server is connected or timeout of 3 sec*/
230  if (Cond_Var[m_connectionId].wait_for(
231  mlock, std::chrono::seconds(3),
232  std::bind(&Network::isServer_Connected, this)) == false) {
233  Server_Connected[m_connectionId] = false;
234  return -1;
235  } else if (command_socket.at(m_connectionId) != NULL) {
236  /*Wait for Server message to check another client is connected already
237  * or not*/
238  send_buff[m_connectionId].set_func_name("ServerConnect");
239  send_buff[m_connectionId].set_expect_reply(true);
240  if (SendCommand() != 0) {
241  LOG(ERROR) << "Send Command Failed";
242  Server_Connected[m_connectionId] = false;
243  return -1;
244  }
245  if (recv_server_data() == 0) {
246  /*Data received correctly*/
247  if (strcmp(recv_buff[m_connectionId].message().c_str(),
248  server_msg) == 0) {
249  /*Server is connected successfully*/
250  cout << "Conn established" << endl;
251 
252  return 0;
253  } else {
254  /*Another client is connected already*/
255  cout << "Server Message :: "
256  << recv_buff[m_connectionId].message() << endl;
257  Server_Connected[m_connectionId] = false;
258  return -1;
259  }
260  } else {
261  /*No message received from Server*/
262  Server_Connected[m_connectionId] = false;
263  return -1;
264  }
265  } else if (command_socket.at(m_connectionId) == NULL) {
266  Server_Connected[m_connectionId] = false;
267  return -1;
268  }
269 
270  return -1;
271 }
272 
273 /*
274 * sendCommand(): send data to server
275 * Parameters: none
276 * returns: 0 - on success
277  -1 - on error
278 * Desription: This function is used to send the data to connected server.
279 */
280 int Network::SendCommand(void *rawPayload) {
281  int status = -1;
282  uint8_t numRetry = 0;
283  int siz = send_buff[m_connectionId].ByteSize();
284  unsigned char *pkt = new unsigned char[siz];
285 
287  CodedOutputStream *coded_output = new CodedOutputStream(&aos);
288  send_buff[m_connectionId].SerializeToCodedStream(coded_output);
289 
290  recv_buff[m_connectionId].Clear();
291 
292  while (numRetry++ < MAX_RETRY_CNT && Server_Connected[m_connectionId]) {
293 
294  zmq::message_t request(pkt, siz);
295  if (command_socket[m_connectionId]->send(request,
296  zmq::send_flags::none)) {
297  status = 0;
298  Send_Successful[m_connectionId] = true;
299  Cond_Var[m_connectionId].notify_all();
300  return status;
301  } else {
302  status = -1; // Timeout occurred
303  break;
304 #ifdef NW_DEBUG
305  std::cout << "Send Timeout error" << std::endl;
306 #endif
307  }
308  }
309 
310  if (!Server_Connected[m_connectionId]) {
311  status = -2;
312  }
313 
314  m_latestActivityTimestamp = std::chrono::steady_clock::now();
315 
316  return status;
317 }
318 
319 /*
320 * recv_server_data(): receive data from server
321 * Parameters: None
322 * returns: 0 - on success
323  -1 - on error
324 * Desription: This function is used to receive the data from connected server
325 */
327  int status = -1;
328  uint8_t numRetry = 0;
329 
330  while (numRetry++ < MAX_RETRY_CNT &&
331  Server_Connected[m_connectionId] != false) {
332 
333  /*Acquire the lock*/
334  std::unique_lock<std::mutex> mlock(mutex_recv[m_connectionId]);
335  if (Cond_Var[m_connectionId].wait_for(
336  mlock, std::chrono::seconds(10),
337  std::bind(&Network::isSend_Successful, this)) == true) {
338  /*reset the flag value to receive again*/
339  Data_Received[m_connectionId] = false;
340 
342 
343  if (command_socket[m_connectionId]->recv(message,
344  zmq::recv_flags::none)) {
345  // Check if data is received correctly
346  if (message.size() >= 0) {
348  static_cast<char *>(message.data()),
349  static_cast<int>(message.size()));
350  CodedInputStream coded_input(&ais);
351  recv_buff[m_connectionId].ParseFromCodedStream(
352  &coded_input);
353 
354  recv_data_error = 0;
355  Data_Received[m_connectionId] = true;
356 
357  if (recv_buff[m_connectionId].interrupt_occured()) {
358  InterruptDetected[m_connectionId] = true;
359  }
360 
361  /*Notify the host SDK that data is received from server*/
362  Cond_Var[m_connectionId].notify_all();
363  status = 0;
364  break;
365  }
366  } else {
367  /*No data received, retry sending command */
368  LOG(INFO)
369  << "Data not received from server going to send again";
370  if (SendCommand() != 0) {
371  status = -1;
372  break;
373  }
374  }
375  } else {
376  /*No data received till timeout, retry sending command */
377  if (SendCommand() != 0) {
378  status = -1;
379  break;
380  }
381  }
382  }
383 
384  if (Server_Connected[m_connectionId] == false) {
385  status = -2;
386  }
387 
388  send_buff[m_connectionId].Clear();
389 
390  if (status == 0) {
391  if (InterruptDetected[m_connectionId]) {
392  InterruptDetected[m_connectionId] = false;
393  if (m_intNotifCb) {
394  m_intNotifCb();
395  }
396  }
397  }
398 
399  m_latestActivityTimestamp = std::chrono::steady_clock::now();
400 
401  return status;
402 }
403 
404 /*
405  * call_zmq_service(): calls zmq service zmq_event_t
406  * Parameters: IP - the ip address of the server to connect to
407  * returns: None
408  * Desription: This function calls zmq_event_t to monitor any event
409  * pending zmq activity
410  */
411 
413  while (running) {
414 
416  zmq::message_t msg;
417  try {
419  if (monitor_sockets[m_connectionId]) {
420  monitor_sockets[m_connectionId]->recv(msg);
421  }
422  } catch (const zmq::error_t &e) {
423  monitor_sockets[m_connectionId]->close();
424  }
425 
426  memcpy(&event, msg.data(), sizeof(event));
427 
428  callback_function(command_socket.at(m_connectionId), event);
429  }
430 }
431 
432 /*
433 * callback_function(): Handles the zmq events
434 * Parameters: stx - socket to monitor
435  reasons - zmq event occurred for stx instance
436 * returns: 0
437 * Desription: This function handles the zmq events and take
438 appropriate action
439 */
440 int Network::callback_function(std::unique_ptr<zmq::socket_t> &stx,
441  const zmq_event_t &reason) {
442 
443  int connectionId = 0;
444  auto status = std::find(command_socket.begin(), command_socket.end(), stx);
445  if (status != command_socket.end()) {
446  connectionId =
447  static_cast<int>(std::distance(command_socket.begin(), status));
448  }
449 
450  // Handle the event based on the connection ID
451  switch (reason.event) {
452  case ZMQ_EVENT_CONNECTED:
453  LOG(INFO) << "Connected to server";
454  Server_Connected[connectionId] = true;
455  Cond_Var[connectionId].notify_all();
456  break;
457  case ZMQ_EVENT_CLOSED:
458  LOG(INFO) << "Closed connection with connection ID: " << connectionId;
459  /*Set a flag to indicate server connection is closed abruptly*/
460  {
461  std::lock_guard<std::recursive_mutex> guard(m_mutex[connectionId]);
462  Server_Connected[connectionId] = false;
463  running = false;
464  command_socket.at(connectionId)->close();
465  monitor_sockets.at(connectionId)->close();
466  contexts.at(connectionId)->close();
467  command_socket.at(connectionId) = NULL;
468  monitor_sockets.at(connectionId) = NULL;
469  contexts.at(connectionId) = NULL;
470  }
471  break;
473  LOG(INFO) << "Connection retried to with connection ID: "
474  << connectionId;
475  break;
477  LOG(INFO) << "Disconnected from server at with connection ID: "
478  << connectionId;
479  /*Set a flag to indicate server connection is closed abruptly*/
480  {
481  std::lock_guard<std::recursive_mutex> guard(m_mutex[connectionId]);
482  Server_Connected[connectionId] = false;
483  running = false;
484  command_socket.at(connectionId)->close();
485  monitor_sockets.at(connectionId)->close();
486  contexts.at(connectionId)->close();
487  command_socket.at(connectionId) = NULL;
488  monitor_sockets.at(connectionId) = NULL;
489  contexts.at(connectionId) = NULL;
490  }
491  break;
493  LOG(INFO) << "Event: CONNECT_DELAYED - Connection attempt delayed, "
494  "server might be unavailable.";
495  {
496  std::lock_guard<std::recursive_mutex> guard(m_mutex[connectionId]);
497  Server_Connected[connectionId] = false;
498  }
499  break;
500  default:
501 #ifdef NW_DEBUG
502  LOG(INFO) << "Event: " << event.event
503  << " on with connection ID: " << connectionId;
504 #endif
505  break;
506  }
507 
508  return 0;
509 }
510 
512  m_intNotifCb = cb;
513 }
514 
515 std::chrono::steady_clock::time_point Network::getLatestActivityTimestamp() {
516  return m_latestActivityTimestamp;
517 }
518 
519 /*
520  * Network(): Initializes the network parameters
521  * Parameters: None
522  * Desription: This function initializes the network parameters
523  */
524 Network::Network(int connectionId)
525  : m_intNotifCb(nullptr), m_latestActivityTimestamp{} {
526 
527  /*Initialize the static flags*/
528  Network::Send_Successful[connectionId] = false;
529  Network::Data_Received[connectionId] = false;
530  Network::Thread_Running[connectionId] = 0;
531  Network::Server_Connected[connectionId] = false;
532  Network::Thread_Detached[connectionId] = false;
533  Network::InterruptDetected[connectionId] = false;
534  running = true;
535 
536  m_connectionId = connectionId;
537  while (contexts.size() <= m_connectionId)
538  contexts.emplace_back(nullptr);
539 }
540 
541 /*
542  * ~Network(): Destructor for network class
543  * Parameters: None
544  * Desription: Destructor for network class
545  */
547  if (contexts.at(m_connectionId) != NULL &&
549 
550  /*set a flag to complete the thread */
551 
553  {
554  std::lock_guard<std::recursive_mutex> guard(
557  running = false;
558  command_socket.at(m_connectionId)->close();
559  monitor_sockets.at(m_connectionId)->close();
560  contexts.at(m_connectionId)->close();
564  }
565  }
566 }
567 
568 int32_t Network::getFrame(uint16_t *buffer, uint32_t buf_size) {
570  if (frame_socket != nullptr) {
571  frame_socket->recv(message, zmq::recv_flags::none);
572  }
573 
574  if (buf_size == message.size()) {
575  memcpy(buffer, message.data(), message.size());
576  } else {
577  LOG(ERROR) << "Received message of size " << message.size()
578  << " bytes . Expected message size " << buf_size
579  << " bytes , dropping the frame.";
580  }
581 
582  return 0;
583 }
584 
586 
587  if (frame_socket) {
588  frame_socket->close(); // Close the socket
589  frame_socket.reset(); // Release the unique pointer
590  }
591 
592  if (zmq_context) {
593  zmq_context.reset(); // Release the ZMQ context
594  }
595 
596  LOG(INFO) << "Frame socket connection closed.";
597 }
598 
600 
601  // Create a ZMQ connection for capturning frame in Async
602  frame_context = std::make_unique<zmq::context_t>(1);
603  frame_socket =
604  std::make_unique<zmq::socket_t>(*frame_context, zmq::socket_type::pull);
605  frame_socket->setsockopt(ZMQ_RCVTIMEO,
606  1100); // TODO: Base ZMQ_RCVTIMEO on the frame rate
607  frame_socket->setsockopt(ZMQ_RCVHWM, (int *)&max_buffer_size,
608  sizeof(max_buffer_size));
609  std::string zmq_address = "tcp://" + ip + ":5555";
610  frame_socket->connect(zmq_address);
611  LOG(INFO) << "Frame Client Connection established.";
612 }
zmq_event_t
Definition: zmq.hpp:208
Network::Cond_Var
static std::condition_variable_any Cond_Var[MAX_CAMERA_NUM]
Definition: network.h:66
Network::callback_function
static int callback_function(std::unique_ptr< zmq::socket_t > &stx, const zmq_event_t &event)
callback_function() - APi to handle zmq events
Definition: network.cpp:440
Network::closeConnectionFrameSocket
void closeConnectionFrameSocket()
closeConnectionFrameSocket() - APi to close the frame socket connection
Definition: network.cpp:585
zmq_ip
std::string zmq_ip
Definition: network.cpp:46
INFO
const int INFO
Definition: log_severity.h:59
Network::command_socket
static std::vector< std::unique_ptr< zmq::socket_t > > command_socket
Definition: network.h:56
Network::isData_Received
bool isData_Received()
Definition: network.cpp:139
zmq::message_t
Definition: zmq.hpp:409
Network::Send_Successful
static bool Send_Successful[MAX_CAMERA_NUM]
Definition: network.h:69
zero_copy_stream_impl.h
Network::registerInterruptCallback
void registerInterruptCallback(InterruptNotificationCallback &cb)
Definition: network.cpp:511
Network::Server_Connected
static bool Server_Connected[MAX_CAMERA_NUM]
Definition: network.h:71
NULL
NULL
Definition: test_security_zap.cpp:405
running
static std::atomic< bool > running
Definition: network.cpp:48
ERROR
const int ERROR
Definition: log_severity.h:60
zmq_socket_monitor
ZMQ_EXPORT int zmq_socket_monitor(void *s_, const char *addr_, int events_)
Definition: zmq.cpp:278
ZMQ_EVENT_CLOSED
#define ZMQ_EVENT_CLOSED
Definition: zmq.h:408
log.h
zmq::message_t::data
void * data() ZMQ_NOTHROW
Definition: zmq.hpp:594
Network::frame_context
std::unique_ptr< zmq::context_t > frame_context
Definition: network.h:60
frame_socket
std::unique_ptr< zmq::socket_t > frame_socket
Definition: network.cpp:44
PROTOCOL_0
@ PROTOCOL_0
Definition: network.cpp:53
Network::Network
Network(int connectionId)
Network() - APi to initialize network parameters.
Definition: network.cpp:524
Network::isThread_Running
bool isThread_Running()
isThread_Running() - APi to check thread exist or not
Definition: network.cpp:109
string
GLsizei const GLchar *const * string
Definition: glcorearb.h:3083
Network::InterruptDetected
static bool InterruptDetected[MAX_CAMERA_NUM]
Definition: network.h:74
send
void send(fd_t fd_, const char(&data_)[N])
Definition: test_security_curve.cpp:209
Network::Thread_Detached
static bool Thread_Detached[MAX_CAMERA_NUM]
Definition: network.h:72
Network::FrameSocketConnection
void FrameSocketConnection(std::string &ip)
FrameSocketConnection() - APi to establish Frame Socket connection.
Definition: network.cpp:599
Network::Thread_Running
int Thread_Running[MAX_CAMERA_NUM]
Definition: network.h:76
Network::ServerConnect
int ServerConnect(const std::string &ip)
Definition: network.cpp:150
ZMQ_REQ
#define ZMQ_REQ
Definition: zmq.h:261
FRAME_PREPADDING_BYTES
static const int FRAME_PREPADDING_BYTES
Definition: network.cpp:78
clientData::data
std::vector< char > data
Definition: network.cpp:61
Network::thread_Cond_Var
static std::condition_variable thread_Cond_Var[MAX_CAMERA_NUM]
Definition: network.h:67
Network::max_buffer_size
int max_buffer_size
Definition: network.h:58
Network::frame_socket
std::unique_ptr< zmq::socket_t > frame_socket
Definition: network.h:59
Network::monitor_sockets
static std::vector< std::unique_ptr< zmq::socket_t > > monitor_sockets
Definition: network.h:57
nBytes
int nBytes
Definition: network.cpp:64
Network::m_mutex
static std::recursive_mutex m_mutex[MAX_CAMERA_NUM]
Definition: network.h:63
recv_data_error
int recv_data_error
Definition: network.cpp:65
ZMQ_RCVHWM
#define ZMQ_RCVHWM
Definition: zmq.h:294
zmq_event_t::event
uint16_t event
Definition: zmq.hpp:210
ZMQ_EVENT_CONNECTED
#define ZMQ_EVENT_CONNECTED
Definition: zmq.h:401
coded_stream.h
event
struct _cl_event * event
Definition: glcorearb.h:4163
Network::recv_server_data
int recv_server_data()
recv_server_data() - APi to receive data from server
Definition: network.cpp:326
google::protobuf::io
Definition: code_generator.h:51
server_msg
char server_msg[]
Definition: network.cpp:66
zmq::error_t::num
int num() const ZMQ_NOTHROW
Definition: zmq.hpp:299
Network::getLatestActivityTimestamp
std::chrono::steady_clock::time_point getLatestActivityTimestamp()
Definition: network.cpp:515
google::protobuf::io::ArrayOutputStream
Definition: zero_copy_stream_impl_lite.h:99
google::protobuf::io::ArrayInputStream
Definition: zero_copy_stream_impl_lite.h:65
Network::isServer_Connected
bool isServer_Connected()
isServer_Connected() - APi to check if server is connected successfully
Definition: network.cpp:97
Network::call_zmq_service
void call_zmq_service(const std::string &ip)
Definition: network.cpp:412
PROTOCOL_COUNT
@ PROTOCOL_COUNT
Definition: network.cpp:53
buffer
Definition: buffer_processor.h:43
m_connectionList
std::vector< std::string > m_connectionList
Definition: network.cpp:87
MAX_CAMERA_NUM
#define MAX_CAMERA_NUM
Definition: network.h:41
Network::send_buff
static payload::ClientRequest send_buff[MAX_CAMERA_NUM]
Definition: network.h:90
google::protobuf::ERROR
static const LogLevel ERROR
Definition: protobuf/src/google/protobuf/testing/googletest.h:70
Network::m_connectionId
int m_connectionId
Definition: network.h:88
Network::~Network
~Network()
~Network() - destructor for network
Definition: network.cpp:546
clientData
Definition: network.cpp:59
google::protobuf::io::CodedOutputStream
Definition: coded_stream.h:693
zmq_context
std::unique_ptr< zmq::context_t > zmq_context
Definition: network.cpp:45
i
int i
Definition: gmock-matchers_test.cc:764
MAX_RETRY_CNT
#define MAX_RETRY_CNT
Definition: network.cpp:51
ZMQ_EVENT_CONNECT_DELAYED
#define ZMQ_EVENT_CONNECT_DELAYED
Definition: zmq.h:402
LOG
#define LOG(x)
Definition: sdk/include/aditof/log.h:72
ZMQ_PAIR
#define ZMQ_PAIR
Definition: zmq.h:258
ZMQ_RCVTIMEO
#define ZMQ_RCVTIMEO
Definition: zmq.h:296
ZMQ_EVENT_CONNECT_RETRIED
#define ZMQ_EVENT_CONNECT_RETRIED
Definition: zmq.h:403
ZMQ_EVENT_ALL
#define ZMQ_EVENT_ALL
Definition: zmq.h:412
Network::InterruptNotificationCallback
std::function< void(void)> InterruptNotificationCallback
Definition: network.h:52
ZMQ_EVENT_DISCONNECTED
#define ZMQ_EVENT_DISCONNECTED
Definition: zmq.h:410
std
google::protobuf::io::CodedInputStream
Definition: coded_stream.h:173
Network::contexts
static std::vector< std::unique_ptr< zmq::context_t > > contexts
Definition: network.h:55
Network::mutex_recv
static std::mutex mutex_recv[MAX_CAMERA_NUM]
Definition: network.h:64
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
Network::Data_Received
static bool Data_Received[MAX_CAMERA_NUM]
Definition: network.h:70
Network::SendCommand
int SendCommand(void *rawPayload=nullptr)
Definition: network.cpp:280
Network::rawPayloads
static void * rawPayloads[MAX_CAMERA_NUM]
Definition: network.h:78
EHOSTUNREACH
#define EHOSTUNREACH
Definition: zmq.h:152
Network::recv_buff
static payload::ServerResponse recv_buff[MAX_CAMERA_NUM]
Definition: network.h:91
ref
GLint ref
Definition: glcorearb.h:2789
zmq::error_t::what
virtual const char * what() const ZMQ_NOTHROW ZMQ_OVERRIDE
Definition: zmq.hpp:295
clientData::hasFragments
bool hasFragments
Definition: network.cpp:60
zmq::error_t
Definition: zmq.hpp:290
Network::isSend_Successful
bool isSend_Successful()
Definition: network.cpp:126
message
GLenum GLuint GLenum GLsizei const GLchar * message
Definition: glcorearb.h:2695
protocols
protocols
Definition: network.cpp:53


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