HiveMindBridge
Public Member Functions | Private Attributes | List of all members
HiveMindBridge Class Reference

#include <HiveMindBridge.h>

Inheritance diagram for HiveMindBridge:
Inheritance graph
Collaboration diagram for HiveMindBridge:
Collaboration graph

Public Member Functions

 HiveMindBridge (int tcpPort, ILogger &logger, uint32_t keepAliveNbSpin=0)
 
 ~HiveMindBridge ()=default
 
void spin ()
 
void onConnect (std::function< void()> hook)
 
void onDisconnect (std::function< void()> hook)
 
bool onBytesReceived (std::function< void(uint8_t *bytes, uint64_t bytesLength)> callback) override
 
bool onNeighborListUpdated (std::function< void(std::array< uint16_t, NEIGHBORS_MAX_SIZE >, uint64_t bytesLength)> callback)
 
bool onNeighborUpdated (std::function< void(uint16_t neighborId, std::optional< Position > position)> callback)
 
bool registerCustomAction (std::string name, CallbackFunction callback, CallbackArgsManifest manifest)
 
bool registerCustomAction (std::string name, CallbackFunction callback)
 
bool queueAndSend (MessageDTO message)
 
bool sendBytes (uint32_t destinationId, const uint8_t *const payload, uint16_t payloadSize)
 
bool sendNeighborUpdateRequest (uint16_t neighborId)
 
bool sendNeighborListUpdateRequest ()
 

Private Attributes

ILogger & m_logger
 
TCPServer m_tcpServer
 
HiveMindHostDeserializer m_deserializer
 
HiveMindHostSerializer m_serializer
 
UserCallbackMap m_userCallbackMap
 
UserCallRequestHandler m_userCallRequestHandler
 
HiveMindHostApiRequestHandler m_hmRequestHandler
 
HiveMindHostApiResponseHandler m_hmResponseHandler
 
MessageHandler m_messageHandler
 
ThreadSafeQueue< MessageDTO > m_inboundQueue
 
ThreadSafeQueue< OutboundRequestHandlem_outboundQueue
 
HiveMindBridgeImpl m_bridge
 

Additional Inherited Members

- Static Public Attributes inherited from IHiveMindBridge
static constexpr uint16_t NEIGHBORS_MAX_SIZE = NEIGHBORS_LIST_SIZE
 

Constructor & Destructor Documentation

◆ HiveMindBridge()

HiveMindBridge::HiveMindBridge ( int  tcpPort,
ILogger &  logger,
uint32_t  keepAliveNbSpin = 0 
)

Construct a HiveMindBridge

Parameters
tcpPortThe port that the TCP server should listen to
loggerlogger used
keepAliveNbSpinNumber of call to spin before a greet is sent to keep the connection alive. Set to 0 to disable

◆ ~HiveMindBridge()

HiveMindBridge::~HiveMindBridge ( )
default

Member Function Documentation

◆ onBytesReceived()

bool HiveMindBridge::onBytesReceived ( std::function< void(uint8_t *bytes, uint64_t bytesLength)>  callback)
overridevirtual

Register a callback to be run upon reception of an arbitrary bytes payload. The callback only fires when the whole payload was received.

Parameters
callbackThe callback to be called. This function takes a pointer to the bytes payload.
Returns
True if an existing callback function was overwritten, false otherwise

Implements IHiveMindBridge.

Here is the call graph for this function:

◆ onConnect()

void HiveMindBridge::onConnect ( std::function< void()>  callback)
virtual

Register a callback to be run when a TCP connection is established with a client HiveMind

Parameters
callbackThe function to be run

Implements IHiveMindBridge.

Here is the call graph for this function:

◆ onDisconnect()

void HiveMindBridge::onDisconnect ( std::function< void()>  callback)
virtual

Register a callback to be run as soon as the TCP Server notices that the connection was lost.

Parameters
callbackThe function to be run

Implements IHiveMindBridge.

Here is the call graph for this function:

◆ onNeighborListUpdated()

bool HiveMindBridge::onNeighborListUpdated ( std::function< void(std::array< uint16_t, NEIGHBORS_MAX_SIZE >, uint64_t bytesLength)>  callback)
virtual

Register a callback to be run upon reception of a neighbor list.

Parameters
callbackThe callback to be called.
Returns
True if an existing callback function was overwritten, false otherwise

Implements IHiveMindBridge.

Here is the call graph for this function:

◆ onNeighborUpdated()

bool HiveMindBridge::onNeighborUpdated ( std::function< void(uint16_t neighborId, std::optional< Position > position)>  callback)
virtual

Register a callback to be run upon reception of a neignbor's position update.

Parameters
callbackThe callback to be called.
Returns
True if an existing callback function was overwritten, false otherwise

Implements IHiveMindBridge.

Here is the call graph for this function:

◆ queueAndSend()

bool HiveMindBridge::queueAndSend ( MessageDTO  message)
virtual

Send a message asynchronously

Parameters
messageThe message to send
Returns
true if the operation succeded.

Implements IHiveMindBridge.

Here is the call graph for this function:

◆ registerCustomAction() [1/2]

bool HiveMindBridge::registerCustomAction ( std::string  name,
CallbackFunction  callback 
)
virtual

Register a custom action that this robot can accomplish.This is meant to be used with functions that do NOT require arguments. With functions requiring arguments, use registerCustomAction(string, CallbackFunction, manifest).

Parameters
nameThe name of the action (must match across the swarm components)
callbackThe function to be run. This is where the custom robot behaviour is meant to be defined.
Returns
True if an existing callback function was overwritten, false otherwise

Implements IHiveMindBridge.

Here is the call graph for this function:

◆ registerCustomAction() [2/2]

bool HiveMindBridge::registerCustomAction ( std::string  name,
CallbackFunction  callback,
CallbackArgsManifest  manifest 
)
virtual

Register a custom action that this robot can accomplish. This is meant to be used with functions that require arguments (specified in manifest). With void functions, use registerCustomAction(string, CallbackFunction).

Parameters
nameThe name of the action (must match across the swarm components)
callbackThe function to be run. This is where the custom robot behaviour is meant to be defined.
manifestA list describing the callback's expected arguments name and type
Returns
True if an existing callback function was overwritten, false otherwise

Implements IHiveMindBridge.

Here is the call graph for this function:

◆ sendBytes()

bool HiveMindBridge::sendBytes ( uint32_t  destinationId,
const uint8_t *const  payload,
uint16_t  payloadSize 
)
virtual

Send an array of bytes asynchronously

Parameters
destinationIdThe Agent to which the data is to be sent
payloadAn array of bytes
payloadSizeThe length of the array of bytes
Returns

Implements IHiveMindBridge.

Here is the call graph for this function:

◆ sendNeighborListUpdateRequest()

bool HiveMindBridge::sendNeighborListUpdateRequest ( )
virtual

Send a request to the HiveBoard to update the list of neighbors.The response will be received asynchronously and should be handled by a callback provided to onNeighborListUpdated().

Returns

Implements IHiveMindBridge.

Here is the call graph for this function:

◆ sendNeighborUpdateRequest()

bool HiveMindBridge::sendNeighborUpdateRequest ( uint16_t  neighborId)
virtual

Send a request to the HiveBoard to update the position of a given neighbor. The response will be received asynchronously and should be handled by a callback provided to onNeighborUpdated().

Parameters
neighborIdThe ID of the neighbor to update.
Returns
true if the operation succeded.

Implements IHiveMindBridge.

Here is the call graph for this function:

◆ spin()

void HiveMindBridge::spin ( )
virtual

Spin the bridge's applicative loop

Implements IHiveMindBridge.

Here is the call graph for this function:

Member Data Documentation

◆ m_bridge

HiveMindBridgeImpl HiveMindBridge::m_bridge
private

◆ m_deserializer

HiveMindHostDeserializer HiveMindBridge::m_deserializer
private

◆ m_hmRequestHandler

HiveMindHostApiRequestHandler HiveMindBridge::m_hmRequestHandler
private

◆ m_hmResponseHandler

HiveMindHostApiResponseHandler HiveMindBridge::m_hmResponseHandler
private

◆ m_inboundQueue

ThreadSafeQueue<MessageDTO> HiveMindBridge::m_inboundQueue
private

◆ m_logger

ILogger& HiveMindBridge::m_logger
private

◆ m_messageHandler

MessageHandler HiveMindBridge::m_messageHandler
private

◆ m_outboundQueue

ThreadSafeQueue<OutboundRequestHandle> HiveMindBridge::m_outboundQueue
private

◆ m_serializer

HiveMindHostSerializer HiveMindBridge::m_serializer
private

◆ m_tcpServer

TCPServer HiveMindBridge::m_tcpServer
private

◆ m_userCallbackMap

UserCallbackMap HiveMindBridge::m_userCallbackMap
private

◆ m_userCallRequestHandler

UserCallRequestHandler HiveMindBridge::m_userCallRequestHandler
private

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