Public Types | Public Member Functions | Static Public Member Functions | Public Attributes | Static Public Attributes | Private Member Functions | Private Attributes | Static Private Attributes | List of all members
Network Class Reference

#include <network.h>

Public Types

typedef std::function< void(void)> InterruptNotificationCallback
 

Public Member Functions

void closeConnectionFrameSocket ()
 closeConnectionFrameSocket() - APi to close the frame socket connection More...
 
void FrameSocketConnection (std::string &ip)
 FrameSocketConnection() - APi to establish Frame Socket connection. More...
 
int32_t getFrame (uint16_t *buffer, uint32_t buf_size)
 getFrame() - APi to get frame in Async More...
 
std::chrono::steady_clock::time_point getLatestActivityTimestamp ()
 
bool isData_Received ()
 
bool isSend_Successful ()
 
bool isServer_Connected ()
 isServer_Connected() - APi to check if server is connected successfully More...
 
bool isThread_Running ()
 isThread_Running() - APi to check thread exist or not More...
 
 Network (int connectionId)
 Network() - APi to initialize network parameters. More...
 
int recv_server_data ()
 recv_server_data() - APi to receive data from server More...
 
void registerInterruptCallback (InterruptNotificationCallback &cb)
 
int SendCommand (void *rawPayload=nullptr)
 
int ServerConnect (const std::string &ip)
 
 ~Network ()
 ~Network() - destructor for network More...
 

Static Public Member Functions

static int callback_function (std::unique_ptr< zmq::socket_t > &stx, const zmq_event_t &event)
 callback_function() - APi to handle zmq events More...
 

Public Attributes

int m_connectionId
 
int m_frameLength
 

Static Public Attributes

static payload::ServerResponse recv_buff [MAX_CAMERA_NUM]
 
static payload::ClientRequest send_buff [MAX_CAMERA_NUM]
 

Private Member Functions

void call_zmq_service (const std::string &ip)
 

Private Attributes

bool Connection_Closed [MAX_CAMERA_NUM] = {false, false, false, false}
 
std::unique_ptr< zmq::context_tframe_context
 
std::unique_ptr< zmq::socket_tframe_socket
 
InterruptNotificationCallback m_intNotifCb
 
std::chrono::steady_clock::time_point m_latestActivityTimestamp
 
int max_buffer_size = 10
 
std::mutex thread_mutex [MAX_CAMERA_NUM]
 
int Thread_Running [MAX_CAMERA_NUM]
 
std::thread threadObj [MAX_CAMERA_NUM]
 

Static Private Attributes

static std::vector< std::unique_ptr< zmq::socket_t > > command_socket
 
static std::condition_variable_any Cond_Var [MAX_CAMERA_NUM]
 
static std::vector< std::unique_ptr< zmq::context_t > > contexts
 
static bool Data_Received [MAX_CAMERA_NUM]
 
static bool InterruptDetected [MAX_CAMERA_NUM]
 
static std::recursive_mutex m_mutex [MAX_CAMERA_NUM]
 
static std::vector< std::unique_ptr< zmq::socket_t > > monitor_sockets
 
static std::mutex mutex_recv [MAX_CAMERA_NUM]
 
static voidrawPayloads [MAX_CAMERA_NUM]
 
static bool Send_Successful [MAX_CAMERA_NUM]
 
static bool Server_Connected [MAX_CAMERA_NUM]
 
static std::condition_variable thread_Cond_Var [MAX_CAMERA_NUM]
 
static bool Thread_Detached [MAX_CAMERA_NUM]
 

Detailed Description

Definition at line 50 of file network.h.

Member Typedef Documentation

◆ InterruptNotificationCallback

Definition at line 52 of file network.h.

Constructor & Destructor Documentation

◆ Network()

Network::Network ( int  connectionId)

Network() - APi to initialize network parameters.

Definition at line 524 of file network.cpp.

◆ ~Network()

Network::~Network ( )

~Network() - destructor for network

Definition at line 546 of file network.cpp.

Member Function Documentation

◆ call_zmq_service()

void Network::call_zmq_service ( const std::string ip)
private

call_zmq_service - calls zmq_event_t to service any zmq socket events activity

Definition at line 412 of file network.cpp.

◆ callback_function()

int Network::callback_function ( std::unique_ptr< zmq::socket_t > &  stx,
const zmq_event_t event 
)
static

callback_function() - APi to handle zmq events

Definition at line 440 of file network.cpp.

◆ closeConnectionFrameSocket()

void Network::closeConnectionFrameSocket ( )

closeConnectionFrameSocket() - APi to close the frame socket connection

Definition at line 585 of file network.cpp.

◆ FrameSocketConnection()

void Network::FrameSocketConnection ( std::string ip)

FrameSocketConnection() - APi to establish Frame Socket connection.

Definition at line 599 of file network.cpp.

◆ getFrame()

int32_t Network::getFrame ( uint16_t *  buffer,
uint32_t  buf_size 
)

getFrame() - APi to get frame in Async

Definition at line 568 of file network.cpp.

◆ getLatestActivityTimestamp()

std::chrono::steady_clock::time_point Network::getLatestActivityTimestamp ( )

Definition at line 515 of file network.cpp.

◆ isData_Received()

bool Network::isData_Received ( )

isData_Received() - APi to check if data is received from server successfully

Definition at line 139 of file network.cpp.

◆ isSend_Successful()

bool Network::isSend_Successful ( )

isSend_Successful() - APi to check if data has been sent to server successfully

Definition at line 126 of file network.cpp.

◆ isServer_Connected()

bool Network::isServer_Connected ( )

isServer_Connected() - APi to check if server is connected successfully

Definition at line 97 of file network.cpp.

◆ isThread_Running()

bool Network::isThread_Running ( )

isThread_Running() - APi to check thread exist or not

Definition at line 109 of file network.cpp.

◆ recv_server_data()

int Network::recv_server_data ( )

recv_server_data() - APi to receive data from server

Definition at line 326 of file network.cpp.

◆ registerInterruptCallback()

void Network::registerInterruptCallback ( InterruptNotificationCallback cb)

Definition at line 511 of file network.cpp.

◆ SendCommand()

int Network::SendCommand ( void rawPayload = nullptr)

SendCommand() - APi to send SDK apis to connected server If, after the command, we expect the server to send raw (non-protobuf) payload, set the 'rawPayload' with the location where the payload should be copied. Otherwise, set to null or skip it.

Definition at line 280 of file network.cpp.

◆ ServerConnect()

int Network::ServerConnect ( const std::string ip)

ServerConnect() - APi to initialize the zmq sockets and connect to zmq server

Definition at line 150 of file network.cpp.

Member Data Documentation

◆ command_socket

std::vector< std::unique_ptr< zmq::socket_t > > Network::command_socket
staticprivate

Definition at line 56 of file network.h.

◆ Cond_Var

condition_variable_any Network::Cond_Var
staticprivate

Definition at line 66 of file network.h.

◆ Connection_Closed

bool Network::Connection_Closed[MAX_CAMERA_NUM] = {false, false, false, false}
private

Definition at line 73 of file network.h.

◆ contexts

std::vector< std::unique_ptr< zmq::context_t > > Network::contexts
staticprivate

Definition at line 55 of file network.h.

◆ Data_Received

bool Network::Data_Received
staticprivate

Definition at line 70 of file network.h.

◆ frame_context

std::unique_ptr<zmq::context_t> Network::frame_context
private

Definition at line 60 of file network.h.

◆ frame_socket

std::unique_ptr<zmq::socket_t> Network::frame_socket
private

Definition at line 59 of file network.h.

◆ InterruptDetected

bool Network::InterruptDetected
staticprivate

Definition at line 74 of file network.h.

◆ m_connectionId

int Network::m_connectionId

Definition at line 88 of file network.h.

◆ m_frameLength

int Network::m_frameLength

Definition at line 92 of file network.h.

◆ m_intNotifCb

InterruptNotificationCallback Network::m_intNotifCb
private

Definition at line 80 of file network.h.

◆ m_latestActivityTimestamp

std::chrono::steady_clock::time_point Network::m_latestActivityTimestamp
private

Definition at line 81 of file network.h.

◆ m_mutex

recursive_mutex Network::m_mutex
staticprivate

Definition at line 63 of file network.h.

◆ max_buffer_size

int Network::max_buffer_size = 10
private

Definition at line 58 of file network.h.

◆ monitor_sockets

std::vector< std::unique_ptr< zmq::socket_t > > Network::monitor_sockets
staticprivate

Definition at line 57 of file network.h.

◆ mutex_recv

mutex Network::mutex_recv
staticprivate

Definition at line 64 of file network.h.

◆ rawPayloads

void * Network::rawPayloads
staticprivate

Definition at line 78 of file network.h.

◆ recv_buff

ServerResponse Network::recv_buff
static

Definition at line 91 of file network.h.

◆ send_buff

ClientRequest Network::send_buff
static

Definition at line 90 of file network.h.

◆ Send_Successful

bool Network::Send_Successful
staticprivate

Definition at line 69 of file network.h.

◆ Server_Connected

bool Network::Server_Connected
staticprivate

Definition at line 71 of file network.h.

◆ thread_Cond_Var

condition_variable Network::thread_Cond_Var
staticprivate

Definition at line 67 of file network.h.

◆ Thread_Detached

bool Network::Thread_Detached
staticprivate

Definition at line 72 of file network.h.

◆ thread_mutex

std::mutex Network::thread_mutex[MAX_CAMERA_NUM]
private

Definition at line 65 of file network.h.

◆ Thread_Running

int Network::Thread_Running[MAX_CAMERA_NUM]
private

Definition at line 76 of file network.h.

◆ threadObj

std::thread Network::threadObj[MAX_CAMERA_NUM]
private

Definition at line 62 of file network.h.


The documentation for this class was generated from the following files:


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