HiveMindBridge
Public Member Functions | Static Public Attributes | List of all members
IHiveMindBridge Class Referenceabstract

#include <IHiveMindBridge.h>

Inheritance diagram for IHiveMindBridge:
Inheritance graph
Collaboration diagram for IHiveMindBridge:
Collaboration graph

Public Member Functions

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

Static Public Attributes

static constexpr uint16_t NEIGHBORS_MAX_SIZE = NEIGHBORS_LIST_SIZE
 

Detailed Description

The HiveMindBridge is the main entrypoint to the bridge's library. It includes everything necessary to define a custom swarm API and provides some hooks to control the robot when some usual events occur, such as connection or disconnection of a HiveMind.

Member Function Documentation

◆ onBytesReceived()

virtual bool IHiveMindBridge::onBytesReceived ( std::function< void(uint8_t *bytes, uint64_t bytesLength)>  callback)
pure virtual

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

Implemented in HiveMindBridge.

◆ onConnect()

virtual void IHiveMindBridge::onConnect ( std::function< void()>  callback)
pure virtual

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

Parameters
callbackThe function to be run

Implemented in HiveMindBridge.

◆ onDisconnect()

virtual void IHiveMindBridge::onDisconnect ( std::function< void()>  callback)
pure 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

Implemented in HiveMindBridge.

◆ onNeighborListUpdated()

virtual bool IHiveMindBridge::onNeighborListUpdated ( std::function< void(std::array< uint16_t, NEIGHBORS_MAX_SIZE >, uint64_t bytesLength)>  callback)
pure 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

Implemented in HiveMindBridge.

◆ onNeighborUpdated()

virtual bool IHiveMindBridge::onNeighborUpdated ( std::function< void(uint16_t neighborId, std::optional< Position > position)>  callback)
pure 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

Implemented in HiveMindBridge.

◆ queueAndSend()

virtual bool IHiveMindBridge::queueAndSend ( MessageDTO  message)
pure virtual

Send a message asynchronously

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

Implemented in HiveMindBridge.

◆ registerCustomAction() [1/2]

virtual bool IHiveMindBridge::registerCustomAction ( std::string  name,
CallbackFunction  callback 
)
pure 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

Implemented in HiveMindBridge.

◆ registerCustomAction() [2/2]

virtual bool IHiveMindBridge::registerCustomAction ( std::string  name,
CallbackFunction  callback,
CallbackArgsManifest  manifest 
)
pure 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

Implemented in HiveMindBridge.

◆ sendBytes()

virtual bool IHiveMindBridge::sendBytes ( uint32_t  destinationId,
const uint8_t *const  payload,
uint16_t  payloadSize 
)
pure 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

Implemented in HiveMindBridge.

◆ sendNeighborListUpdateRequest()

virtual bool IHiveMindBridge::sendNeighborListUpdateRequest ( )
pure 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

Implemented in HiveMindBridge.

◆ sendNeighborUpdateRequest()

virtual bool IHiveMindBridge::sendNeighborUpdateRequest ( uint16_t  neighborId)
pure 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.

Implemented in HiveMindBridge.

◆ spin()

virtual void IHiveMindBridge::spin ( )
pure virtual

Spin the bridge's applicative loop

Implemented in HiveMindBridge.

Member Data Documentation

◆ NEIGHBORS_MAX_SIZE

constexpr uint16_t IHiveMindBridge::NEIGHBORS_MAX_SIZE = NEIGHBORS_LIST_SIZE
staticconstexpr

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