mavsdk::Mavsdk Class Reference ​
#include: mavsdk.h
This is the main class of MAVSDK (a MAVLink API Library).
It is used to discover vehicles and manage active connections.
An instance of this class must be created and kept alive in order to use the library. The instance can be destroyed after use in order to break connections and release all resources.
Data Structures ​
struct Configuration
struct ConnectionError
Public Types ​
Type | Description |
---|---|
Handle<> ConnectionHandle | Handle type to remove a connection. |
std::function< void(ConnectionError)> ConnectionErrorCallback | |
Handle< ConnectionError > ConnectionErrorHandle | Handle type to remove a connection error subscription. |
std::function< void()> NewSystemCallback | Callback type discover and timeout notifications. |
Handle<> NewSystemHandle | Handle type to unsubscribe from subscribe_on_new_system. |
Public Member Functions ​
Type | Name | Description |
---|---|---|
 | Mavsdk ()=delete | Default constructor without configuration, no longer recommended. |
 | Mavsdk (Configuration configuration) | Constructor with configuration. |
 | ~Mavsdk () | Destructor. |
std::string | version () const | Returns the version of MAVSDK. |
ConnectionResult | add_any_connection (const std::string & connection_url, ForwardingOption forwarding_option=ForwardingOption::ForwardingOff) | Adds Connection via URL. |
std::pair< ConnectionResult, ConnectionHandle > | add_any_connection_with_handle (const std::string & connection_url, ForwardingOption forwarding_option=ForwardingOption::ForwardingOff) | Adds Connection via URL Additionally returns a handle to remove the connection later. |
void | remove_connection (ConnectionHandle handle) | |
ConnectionErrorHandle | subscribe_connection_errors (ConnectionErrorCallback callback) | |
void | unsubscribe_connection_errors (ConnectionErrorHandle handle) | |
std::vector< std::shared_ptr< System > > | systems () const | Get a vector of systems which have been discovered or set-up. |
std::optional< std::shared_ptr< System > > | first_autopilot (double timeout_s)const | Get the first autopilot that has been discovered. |
void | set_configuration (Configuration configuration) | Set Configuration of SDK. |
void | set_timeout_s (double timeout_s) | Set timeout of MAVLink transfers. |
NewSystemHandle | subscribe_on_new_system (const NewSystemCallback & callback) | Get notification about a change in systems. |
void | unsubscribe_on_new_system (NewSystemHandle handle) | unsubscribe from subscribe_on_new_system. |
std::shared_ptr< ServerComponent > | server_component (unsigned instance=0) | Get server component with default type of Mavsdk instance. |
std::shared_ptr< ServerComponent > | server_component_by_type (ComponentType component_type, unsigned instance=0) | Get server component by a high level type. |
std::shared_ptr< ServerComponent > | server_component_by_id (uint8_t component_id) | Get server component by the low MAVLink component ID. |
void | intercept_incoming_messages_async (std::function< bool(mavlink_message_t &)> callback) | Intercept incoming messages. |
void | intercept_outgoing_messages_async (std::function< bool(mavlink_message_t &)> callback) | Intercept outgoing messages. |
Constructor & Destructor Documentation ​
Mavsdk() ​
mavsdk::Mavsdk::Mavsdk()=delete
Default constructor without configuration, no longer recommended.
INFO
This has been removed because MAVSDK used to identify itself as a ground station by default which isn't always the safest choice. For instance, when MAVSDK is used on a companion computer (set as a ground station) it means that the appropriate failsafe doesn't trigger.
Mavsdk() ​
mavsdk::Mavsdk::Mavsdk(Configuration configuration)
Constructor with configuration.
Parameters
- Configuration configuration - Configuration to use in MAVSDK instance.
~Mavsdk() ​
mavsdk::Mavsdk::~Mavsdk()
Destructor.
Disconnects all connected vehicles and releases all resources.
Member Typdef Documentation ​
typedef ConnectionHandle ​
using mavsdk::Mavsdk::ConnectionHandle = Handle<>
Handle type to remove a connection.
typedef ConnectionErrorCallback ​
using mavsdk::Mavsdk::ConnectionErrorCallback = std::function<void(ConnectionError)>
Connection Error callback type
typedef ConnectionErrorHandle ​
using mavsdk::Mavsdk::ConnectionErrorHandle = Handle<ConnectionError>
Handle type to remove a connection error subscription.
typedef NewSystemCallback ​
using mavsdk::Mavsdk::NewSystemCallback = std::function<void()>
Callback type discover and timeout notifications.
typedef NewSystemHandle ​
using mavsdk::Mavsdk::NewSystemHandle = Handle<>
Handle type to unsubscribe from subscribe_on_new_system.
Member Function Documentation ​
version() ​
std::string mavsdk::Mavsdk::version() const
Returns the version of MAVSDK.
Note, you're not supposed to request the version too many times.
Returns
 std::string - A string containing the version.
add_any_connection() ​
ConnectionResult mavsdk::Mavsdk::add_any_connection(const std::string &connection_url, ForwardingOption forwarding_option=ForwardingOption::ForwardingOff)
Adds Connection via URL.
Supports connection: Serial, TCP or UDP. Connection URL format should be:
UDP in (server): udpin://our_ip:port
UDP out (client): udpout://remote_ip:port
TCP in (server): tcpin://our_ip:port
TCP out (client): tcpout://remote_ip:port
Serial: serial://dev_node:baudrate
Serial with flow control: serial_flowcontrol://dev_node:baudrate
For UDP in and TCP in (as server), our IP can be set to:
0.0.0.0: listen on all interfaces
127.0.0.1: listen on loopback (local) interface only
Our IP: (e.g. 192.168.1.12): listen only on the network interface with this IP.
For UDP out and TCP out, the IP needs to be set to the remote IP, where the MAVLink messages are to be sent to.
Parameters
- const std::string& connection_url - connection URL string.
- ForwardingOption forwarding_option - message forwarding option (when multiple interfaces are used).
Returns
 ConnectionResult - The result of adding the connection.
add_any_connection_with_handle() ​
std::pair< ConnectionResult, ConnectionHandle > mavsdk::Mavsdk::add_any_connection_with_handle(const std::string &connection_url, ForwardingOption forwarding_option=ForwardingOption::ForwardingOff)
Adds Connection via URL Additionally returns a handle to remove the connection later.
Supports connection: Serial, TCP or UDP. Connection URL format should be:
UDP in (server): udpin://our_ip:port
UDP out (client): udpout://remote_ip:port
TCP in (server): tcpin://our_ip:port
TCP out (client): tcpout://remote_ip:port
Serial: serial://dev_node:baudrate
Serial with flow control: serial_flowcontrol://dev_node:baudrate
For UDP in and TCP in (as server), our IP can be set to:
0.0.0.0: listen on all interfaces
127.0.0.1: listen on loopback (local) interface only
Our IP: (e.g. 192.168.1.12): listen only on the network interface with this IP.
For UDP out and TCP out, the IP needs to be set to the remote IP, where the MAVLink messages are to be sent to.
Parameters
- const std::string& connection_url - connection URL string.
- ForwardingOption forwarding_option - message forwarding option (when multiple interfaces are used).
Returns
 std::pair< ConnectionResult, ConnectionHandle > - A pair containing the result of adding the connection as well as a handle to remove it later.
remove_connection() ​
void mavsdk::Mavsdk::remove_connection(ConnectionHandle handle)
Remove connection again.
Parameters
- ConnectionHandle handle - Handle returned when connection was added.
subscribe_connection_errors() ​
ConnectionErrorHandle mavsdk::Mavsdk::subscribe_connection_errors(ConnectionErrorCallback callback)
Subscribe to connection errors.
This will trigger when messages fail to be sent which can help diagnosing network interfaces or serial devices disappearing.
Usually, an error will require to remove a connection and add it fresh.
Parameters
- ConnectionErrorCallback callback - Callback to subscribe.
Returns
 ConnectionErrorHandle - Handle to unsubscribe again.
unsubscribe_connection_errors() ​
void mavsdk::Mavsdk::unsubscribe_connection_errors(ConnectionErrorHandle handle)
Unsubscribe from connection errors.
Parameters
- ConnectionErrorHandle handle - Handle to unsubscribe.
systems() ​
std::vector< std::shared_ptr< System > > mavsdk::Mavsdk::systems() const
Get a vector of systems which have been discovered or set-up.
Returns
 std::vector< std::shared_ptr< System > > - The vector of systems which are available.
first_autopilot() ​
std::optional< std::shared_ptr< System > > mavsdk::Mavsdk::first_autopilot(double timeout_s) const
Get the first autopilot that has been discovered.
INFO
This requires a MAVLink component with component ID 1 sending heartbeats.
Parameters
- double timeout_s - A timeout in seconds. A timeout of 0 will not wait and return immediately. A negative timeout will wait forever.
Returns
 std::optional< std::shared_ptr< System > > - A system or nothing if nothing was discovered within the timeout.
set_configuration() ​
void mavsdk::Mavsdk::set_configuration(Configuration configuration)
Set Configuration of SDK.
The default configuration is Configuration::GroundStation
The configuration is used in order to set the MAVLink system ID, the component ID, as well as the MAV_TYPE accordingly.
Parameters
- Configuration configuration - Configuration chosen.
set_timeout_s() ​
void mavsdk::Mavsdk::set_timeout_s(double timeout_s)
Set timeout of MAVLink transfers.
The default timeout used is generally DEFAULT_SERIAL_BAUDRATE (0.5 seconds) seconds. If MAVSDK is used on the same host this timeout can be reduced, while if MAVSDK has to communicate over links with high latency it might need to be increased to prevent timeouts.
Parameters
- double timeout_s -
subscribe_on_new_system() ​
NewSystemHandle mavsdk::Mavsdk::subscribe_on_new_system(const NewSystemCallback &callback)
Get notification about a change in systems.
This gets called whenever a system is added.
Parameters
- const NewSystemCallback& callback - Callback to subscribe.
Returns
 NewSystemHandle - A handle to unsubscribe again.
unsubscribe_on_new_system() ​
void mavsdk::Mavsdk::unsubscribe_on_new_system(NewSystemHandle handle)
unsubscribe from subscribe_on_new_system.
Parameters
- NewSystemHandle handle - Handle received on subscription.
server_component() ​
std::shared_ptr< ServerComponent > mavsdk::Mavsdk::server_component(unsigned instance=0)
Get server component with default type of Mavsdk instance.
Parameters
- unsigned instance -
Returns
 std::shared_ptr< ServerComponent > - A valid shared pointer to a server component if it was successful, an empty pointer otherwise.
server_component_by_type() ​
std::shared_ptr< ServerComponent > mavsdk::Mavsdk::server_component_by_type(ComponentType component_type, unsigned instance=0)
Get server component by a high level type.
This represents a server component of the MAVSDK instance.
Parameters
- ComponentType component_type - The high level type of the component.
- unsigned instance - The instance of the component if there are multiple, starting at 0.
Returns
 std::shared_ptr< ServerComponent > - A valid shared pointer to a server component if it was successful, an empty pointer otherwise.
server_component_by_id() ​
std::shared_ptr< ServerComponent > mavsdk::Mavsdk::server_component_by_id(uint8_t component_id)
Get server component by the low MAVLink component ID.
This represents a server component of the MAVSDK instance.
Parameters
- uint8_t component_id - MAVLink component ID to use
Returns
 std::shared_ptr< ServerComponent > - A valid shared pointer to a server component if it was successful, an empty pointer otherwise.
intercept_incoming_messages_async() ​
void mavsdk::Mavsdk::intercept_incoming_messages_async(std::function< bool(mavlink_message_t &)> callback)
Intercept incoming messages.
This is a hook which allows to change or drop MAVLink messages as they are received before they get forwarded any subscribers.
INFO
This functionality is provided primarily for testing in order to simulate packet drops or actors not adhering to the MAVLink protocols.
Parameters
- std::function< bool(mavlink_message_t &)> callback - Callback to be called for each incoming message. To drop a message, return 'false' from the callback.
intercept_outgoing_messages_async() ​
void mavsdk::Mavsdk::intercept_outgoing_messages_async(std::function< bool(mavlink_message_t &)> callback)
Intercept outgoing messages.
This is a hook which allows to change or drop MAVLink messages before they are sent.
INFO
This functionality is provided primarily for testing in order to simulate packet drops or actors not adhering to the MAVLink protocols.
Parameters
- std::function< bool(mavlink_message_t &)> callback - Callback to be called for each outgoing message. To drop a message, return 'false' from the callback.