#include <IHiveMindBridge.h>
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.
◆ 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
-
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
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
-
callback | The 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
-
callback | The 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
-
callback | The 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
-
callback | The 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
-
message | The 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
-
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
Implemented in HiveMindBridge.
◆ 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
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
-
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
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
-
neighborId | The ID of the neighbor to update. |
- Returns
- true if the operation succeded.
Implemented in HiveMindBridge.
◆ spin()
virtual void IHiveMindBridge::spin |
( |
| ) |
|
|
pure virtual |
◆ 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: