#include <HiveMindBridge.h>
|
| 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 () |
|
◆ HiveMindBridge()
HiveMindBridge::HiveMindBridge |
( |
int |
tcpPort, |
|
|
ILogger & |
logger, |
|
|
uint32_t |
keepAliveNbSpin = 0 |
|
) |
| |
Construct a HiveMindBridge
- Parameters
-
tcpPort | The port that the TCP server should listen to |
logger | logger used |
keepAliveNbSpin | Number of call to spin before a greet is sent to keep the connection alive. Set to 0 to disable |
◆ ~HiveMindBridge()
HiveMindBridge::~HiveMindBridge |
( |
| ) |
|
|
default |
◆ 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
-
callback | The 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.
◆ 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
-
callback | The function to be run |
Implements IHiveMindBridge.
◆ 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
-
callback | The function to be run |
Implements IHiveMindBridge.
◆ 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
-
callback | The callback to be called. |
- Returns
- True if an existing callback function was overwritten, false otherwise
Implements IHiveMindBridge.
◆ 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
-
callback | The callback to be called. |
- Returns
- True if an existing callback function was overwritten, false otherwise
Implements IHiveMindBridge.
◆ queueAndSend()
bool HiveMindBridge::queueAndSend |
( |
MessageDTO |
message | ) |
|
|
virtual |
Send a message asynchronously
- Parameters
-
message | The message to send |
- Returns
- true if the operation succeded.
Implements IHiveMindBridge.
◆ 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
-
name | The name of the action (must match across the swarm components) |
callback | The 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.
◆ registerCustomAction() [2/2]
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
-
name | The name of the action (must match across the swarm components) |
callback | The function to be run. This is where the custom robot behaviour is meant to be defined. |
manifest | A list describing the callback's expected arguments name and type |
- Returns
- True if an existing callback function was overwritten, false otherwise
Implements IHiveMindBridge.
◆ sendBytes()
bool HiveMindBridge::sendBytes |
( |
uint32_t |
destinationId, |
|
|
const uint8_t *const |
payload, |
|
|
uint16_t |
payloadSize |
|
) |
| |
|
virtual |
Send an array of bytes asynchronously
- Parameters
-
destinationId | The Agent to which the data is to be sent |
payload | An array of bytes |
payloadSize | The length of the array of bytes |
- Returns
Implements IHiveMindBridge.
◆ 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.
◆ 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
-
neighborId | The ID of the neighbor to update. |
- Returns
- true if the operation succeded.
Implements IHiveMindBridge.
◆ spin()
void HiveMindBridge::spin |
( |
| ) |
|
|
virtual |
◆ m_bridge
◆ m_deserializer
HiveMindHostDeserializer HiveMindBridge::m_deserializer |
|
private |
◆ m_hmRequestHandler
◆ m_hmResponseHandler
◆ m_inboundQueue
◆ m_logger
ILogger& HiveMindBridge::m_logger |
|
private |
◆ m_messageHandler
◆ m_outboundQueue
◆ m_serializer
HiveMindHostSerializer HiveMindBridge::m_serializer |
|
private |
◆ m_tcpServer
◆ m_userCallbackMap
◆ m_userCallRequestHandler
The documentation for this class was generated from the following files: