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.
Public Types
Type | Description |
---|---|
enum ComponentType | Component Types. |
std::function< void(bool)> IsConnectedCallback | type for is connected callback. |
Handle< bool > IsConnectedHandle | handle type to unsubscribe from subscribe_is_connected. |
std::function< void(ComponentType)> ComponentDiscoveredCallback | type for component discovery callback |
Handle< ComponentType > ComponentDiscoveredHandle | type for component discovery callback handle |
std::function< void(ComponentType, uint8_t)> ComponentDiscoveredIdCallback | type for component discovery callback with component ID |
Handle< ComponentType, uint8_t > ComponentDiscoveredIdHandle | type for component discovery callback handle with component ID |
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)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. |
IsConnectedHandle | subscribe_is_connected (const IsConnectedCallback & callback) | Subscribe to callback to be called when system connection state changes. |
void | unsubscribe_is_connected (IsConnectedHandle handle) | Unsubscribe from subscribe_is_connected. |
ComponentDiscoveredHandle | subscribe_component_discovered (const ComponentDiscoveredCallback & callback) | Subscribe to be called when a component is discovered. |
void | unsubscribe_component_discovered (ComponentDiscoveredHandle handle) | Unsubscribe from subscribe_component_discovered. |
ComponentDiscoveredIdHandle | subscribe_component_discovered_id (const ComponentDiscoveredIdCallback & callback) | Subscribe to be called when a component is discovered. |
void | unsubscribe_component_discovered_id (ComponentDiscoveredIdHandle handle) | Unsubscribe from subscribe_component_discovered_id. |
void | enable_timesync () | Enable time synchronization using the TIMESYNC messages. |
const System & | operator= (const System &)=delete | Equality operator (object is not copyable). |
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 IsConnectedHandle
using mavsdk::System::IsConnectedHandle = Handle<bool>
handle type to unsubscribe from subscribe_is_connected.
typedef ComponentDiscoveredCallback
using mavsdk::System::ComponentDiscoveredCallback = std::function<void(ComponentType)>
type for component discovery callback
typedef ComponentDiscoveredHandle
using mavsdk::System::ComponentDiscoveredHandle = Handle<ComponentType>
type for component discovery callback handle
typedef ComponentDiscoveredIdCallback
using mavsdk::System::ComponentDiscoveredIdCallback = std::function<void(ComponentType, uint8_t)>
type for component discovery callback with component ID
typedef ComponentDiscoveredIdHandle
using mavsdk::System::ComponentDiscoveredIdHandle = Handle<ComponentType, uint8_t>
type for component discovery callback handle with component ID
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) 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.
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()
IsConnectedHandle mavsdk::System::subscribe_is_connected(const IsConnectedCallback &callback)
Subscribe to callback to be called when system connection state changes.
Parameters
- const IsConnectedCallback& callback - Callback which will be called.
Returns
unsubscribe_is_connected()
void mavsdk::System::unsubscribe_is_connected(IsConnectedHandle handle)
Unsubscribe from subscribe_is_connected.
Parameters
- IsConnectedHandle handle -
subscribe_component_discovered()
ComponentDiscoveredHandle mavsdk::System::subscribe_component_discovered(const ComponentDiscoveredCallback &callback)
Subscribe to be called when a component is discovered.
Parameters
- const ComponentDiscoveredCallback& callback - a function of type void(ComponentType) which will be called with the component type of the new component.
Returns
unsubscribe_component_discovered()
void mavsdk::System::unsubscribe_component_discovered(ComponentDiscoveredHandle handle)
Unsubscribe from subscribe_component_discovered.
Parameters
- ComponentDiscoveredHandle handle -
subscribe_component_discovered_id()
ComponentDiscoveredIdHandle mavsdk::System::subscribe_component_discovered_id(const ComponentDiscoveredIdCallback &callback)
Subscribe to be called when a component is discovered.
Parameters
- const ComponentDiscoveredIdCallback& callback - a function of type void(ComponentType) which will be called with the component type and the component id of the new component.
Returns
unsubscribe_component_discovered_id()
void mavsdk::System::unsubscribe_component_discovered_id(ComponentDiscoveredIdHandle handle)
Unsubscribe from subscribe_component_discovered_id.
Parameters
- ComponentDiscoveredIdHandle handle -
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 & -