The interface for retrieving general system information of an Avular robot. More...
#include <creos/system_info_interface.hpp>
Public Member Functions | |
| virtual SubscriptionId | subscribeToSystemInfo (const std::function< void(const creos_messages::SystemInfo &)> &callback)=0 |
| Subscribe to system info messages. | |
| virtual creos_messages::SystemInfo | getSystemInfo (int timeout_ms=1500)=0 |
| Get the system info. | |
| virtual SubscriptionId | subscribeToBatteryStatus (const std::function< void(const creos_messages::BatteryStatus &)> &callback)=0 |
| Subscribe to battery status updates. | |
| virtual creos_messages::BatteryStatus | getBatteryStatus (int timeout_ms=1500)=0 |
| Get the battery status. | |
Static Public Attributes | |
| static constexpr char | name [] = "system_info" |
| static constexpr unsigned | version = 1 |
The interface for retrieving general system information of an Avular robot.
|
pure virtualOriginVertex |
Get the battery status.
The battery status contains information about the battery, like the state and alerts. This function will block until the battery status is received.
| timeout_ms | The time in milliseconds to wait for the battery status. |
| creos::TimeoutError | If the battery status is not received within the timeout. |
| creos::UnsupportedError | If the robot does not provide this data, or the client and agent are incompatible. |
| creos::Exception | if any other error occurred while getting the data. |
|
pure virtualOriginVertex |
Get the system info.
The system info contains information about the connected system, like the name and serial number. This function will block until the system info is received.
| timeout_ms | The time in milliseconds to wait for the system info. |
| creos::TimeoutError | If the system info is not received within the timeout. |
| creos::UnsupportedError | If the robot does not provide this data, or the client and agent are incompatible. |
| creos::Exception | if any other error occurred while getting the data. |
|
pure virtualOriginVertex |
Subscribe to battery status updates.
The battery status contains information about the battery, like the state and alerts.
| callback | The callback function that will be called when new data is available. |
| creos::UnsupportedError | If the robot does not provide this data, or the client and agent are incompatible. |
| creos::SubscriptionError | If the subscription failed to be created. |
|
pure virtualOriginVertex |
Subscribe to system info messages.
The system info messages contain information about the connected system, like the name and serial number.
| callback | The callback function that will be called when new data is available. |
| creos::UnsupportedError | If the robot does not provide this data, or the client and agent are incompatible. |
| creos::SubscriptionError | If the subscription failed to be created. |