mavsdk::System Class Reference
#include: system.h
This class represents a system, made up of one or more components (e.g. autopilot, cameras, servos, gimbals, etc).
System objects are used to interact with UAVs (including their components) and standalone cameras. They are not created directly by application code, but are returned by the Mavsdk class.
Data Structures
struct AutopilotVersion
Public Types
Type | Description |
---|---|
enum ComponentType | Component Types. |
std::function< void(bool)> IsConnectedCallback | type for is connected callback. |
std::function< void(ComponentType)> DiscoverCallback | type for component discovery callback |
std::function< void(ComponentType, uint8_t)> DiscoverIdCallback | type for component discovery callback |
Public Member Functions
Type | Name | Description |
---|---|---|
~System () | Destructor. | |
System (const System &)=delete | Copy constructor (object is not copyable). | |
void | init (uint8_t system_id, uint8_t component_id, bool connected)const | Initialize the system. |
bool | has_autopilot () const | Checks whether the system has an autopilot. |
bool | is_standalone () const | Checks whether the system is a standalone (non-autopilot). |
bool | has_camera (int camera_id=-1)const | Checks whether the system has a camera with the given camera ID. |
bool | has_gimbal () const | Checks whether the system has a gimbal. |
bool | is_connected () const | Checks if the system is connected. |
uint8_t | get_system_id () const | MAVLink System ID of connected system. |
std::vector< uint8_t > | component_ids () const | MAVLink component IDs of connected system. |
void | subscribe_is_connected (IsConnectedCallback callback) | Subscribe to callback to be called when system connection state changes. |
void | register_component_discovered_callback (DiscoverCallback callback)const | Register a callback to be called when a component is discovered. |
void | register_component_discovered_id_callback (DiscoverIdCallback callback)const | Register a callback to be called when a component is discovered. |
void | enable_timesync () | Enable time synchronization using the TIMESYNC messages. |
const System & | operator= (const System &)=delete | Equality operator (object is not copyable). |
void | add_capabilities (uint64_t capabilities) | Register capabilities to the system (only used if MAVSDK is autopilot) |
void | set_flight_sw_version (uint32_t flight_sw_version) | Set flight sw version (only used if MAVSDK is autopilot) |
void | set_middleware_sw_version (uint32_t middleware_sw_version) | Set middleware sw version (only used if MAVSDK is autopilot) |
void | set_os_sw_version (uint32_t os_sw_version) | Set OS sw version (only used if MAVSDK is autopilot) |
void | set_board_version (uint32_t board_version) | Set hardware board version (only used if MAVSDK is autopilot) |
void | set_vendor_id (uint16_t vendor_id) | Set vendor id (only used if MAVSDK is autopilot) |
void | set_product_id (uint16_t product_id) | Set product id (only used if MAVSDK is autopilot) |
bool | set_uid2 (std::string uid2) | Set uid2, 18 chars max (only used if MAVSDK is autopilot) |
AutopilotVersion | get_autopilot_version_data () | Get autopilot version data. |
Constructor & Destructor Documentation
~System()
mavsdk::System::~System()
Destructor.
System()
mavsdk::System::System(const System &)=delete
Copy constructor (object is not copyable).
Parameters
- const System& -
Member Typdef Documentation
typedef IsConnectedCallback
using mavsdk::System::IsConnectedCallback = std::function<void(bool)>
type for is connected callback.
typedef DiscoverCallback
using mavsdk::System::DiscoverCallback = std::function<void(ComponentType)>
type for component discovery callback
typedef DiscoverIdCallback
using mavsdk::System::DiscoverIdCallback = std::function<void(ComponentType, uint8_t)>
type for component discovery callback
Member Enumeration Documentation
enum ComponentType
Component Types.
Value | Description |
---|---|
UNKNOWN |
|
AUTOPILOT |
|
CAMERA |
|
GIMBAL |
Member Function Documentation
init()
void mavsdk::System::init(uint8_t system_id, uint8_t component_id, bool connected) const
Initialize the system.
This is not (and should not be) directly called by application code.
Parameters
- uint8_t system_id - System id.
- uint8_t component_id - Component id.
- bool connected - If true then the system doesn't wait for heartbeat to go into connected state
has_autopilot()
bool mavsdk::System::has_autopilot() const
Checks whether the system has an autopilot.
Returns
bool - true
if it has an autopilot, false
otherwise.
is_standalone()
bool mavsdk::System::is_standalone() const
Checks whether the system is a standalone (non-autopilot).
Returns
bool - true
if stand alone, false
otherwise.
has_camera()
bool mavsdk::System::has_camera(int camera_id=-1) const
Checks whether the system has a camera with the given camera ID.
A System may have several cameras, with IDs starting from 0. When called without passing a camera ID, it checks whether the system has any camera.
Parameters
- int camera_id - ID of the camera starting from 0 onwards.
Returns
bool - true
if camera with the given camera ID is found, false
otherwise.
has_gimbal()
bool mavsdk::System::has_gimbal() const
Checks whether the system has a gimbal.
Returns
bool - true
if the system has a gimbal, false otherwise.
is_connected()
bool mavsdk::System::is_connected() const
Checks if the system is connected.
A system is connected when heartbeats are arriving (discovered and not timed out).
Returns
bool - true
if the system is connected.
get_system_id()
uint8_t mavsdk::System::get_system_id() const
MAVLink System ID of connected system.
: this is 0 if nothing is connected yet.
Returns
uint8_t - the system ID.
component_ids()
std::vector<uint8_t> mavsdk::System::component_ids() const
MAVLink component IDs of connected system.
: all components that have been seen at least once will be listed.
Returns
std::vector< uint8_t > - a list of all component ids
subscribe_is_connected()
void mavsdk::System::subscribe_is_connected(IsConnectedCallback callback)
Subscribe to callback to be called when system connection state changes.
Parameters
- IsConnectedCallback callback - Callback which will be called.
register_component_discovered_callback()
void mavsdk::System::register_component_discovered_callback(DiscoverCallback callback) const
Register a callback to be called when a component is discovered.
Parameters
- DiscoverCallback callback - a function of type void(ComponentType) which will be called with the component type of the new component.
register_component_discovered_id_callback()
void mavsdk::System::register_component_discovered_id_callback(DiscoverIdCallback callback) const
Register a callback to be called when a component is discovered.
Parameters
- DiscoverIdCallback callback - a function of type void(ComponentType) which will be called with the component type and the component id of the new component.
enable_timesync()
void mavsdk::System::enable_timesync()
Enable time synchronization using the TIMESYNC messages.
operator=()
const System& mavsdk::System::operator=(const System &)=delete
Equality operator (object is not copyable).
Parameters
- const System& -
Returns
const System & -
add_capabilities()
void mavsdk::System::add_capabilities(uint64_t capabilities)
Register capabilities to the system (only used if MAVSDK is autopilot)
Plugins should register additional capabilities they provide using this.
Parameters
- uint64_t capabilities - MAVLink capability flag to bitwise OR
set_flight_sw_version()
void mavsdk::System::set_flight_sw_version(uint32_t flight_sw_version)
Set flight sw version (only used if MAVSDK is autopilot)
Parameters
- uint32_t flight_sw_version - version number of flight control software
set_middleware_sw_version()
void mavsdk::System::set_middleware_sw_version(uint32_t middleware_sw_version)
Set middleware sw version (only used if MAVSDK is autopilot)
Parameters
- uint32_t middleware_sw_version - version number of middleware software
set_os_sw_version()
void mavsdk::System::set_os_sw_version(uint32_t os_sw_version)
Set OS sw version (only used if MAVSDK is autopilot)
Parameters
- uint32_t os_sw_version - version number of operating system
set_board_version()
void mavsdk::System::set_board_version(uint32_t board_version)
Set hardware board version (only used if MAVSDK is autopilot)
Parameters
- uint32_t board_version - version number of hardware board
set_vendor_id()
void mavsdk::System::set_vendor_id(uint16_t vendor_id)
Set vendor id (only used if MAVSDK is autopilot)
Parameters
- uint16_t vendor_id - number of vendor id
set_product_id()
void mavsdk::System::set_product_id(uint16_t product_id)
Set product id (only used if MAVSDK is autopilot)
Parameters
- uint16_t product_id - number of product id
set_uid2()
bool mavsdk::System::set_uid2(std::string uid2)
Set uid2, 18 chars max (only used if MAVSDK is autopilot)
Parameters
- std::string uid2 - unique hardware id
Returns
bool - true if valid size, false if too large,
get_autopilot_version_data()
AutopilotVersion mavsdk::System::get_autopilot_version_data()
Get autopilot version data.
Returns
AutopilotVersion - AutopilotVersion struct containing autopilot version ids