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 (first) in order to use the library. The instance must be destroyed after use in order to break connections and release all resources.
Data Structures
struct Configuration
Public Types
Type | Description |
---|---|
enum ComponentType | ComponentType of configurations, used for automatic ID setting. |
Handle<> ConnectionHandle | Handle type to remove a connection. |
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. |
ConnectionResult | add_udp_connection (int local_port=DEFAULT_UDP_PORT, ForwardingOption forwarding_option=ForwardingOption::ForwardingOff) | Adds a UDP connection to the specified port number. |
ConnectionResult | add_udp_connection (const std::string & local_ip, int local_port=DEFAULT_UDP_PORT, ForwardingOption forwarding_option=ForwardingOption::ForwardingOff) | Adds a UDP connection to the specified port number and local interface. |
ConnectionResult | setup_udp_remote (const std::string & remote_ip, int remote_port, ForwardingOption forwarding_option=ForwardingOption::ForwardingOff) | Sets up instance to send heartbeats to the specified remote interface and port number. |
ConnectionResult | add_tcp_connection (const std::string & remote_ip, int remote_port=DEFAULT_TCP_REMOTE_PORT, ForwardingOption forwarding_option=ForwardingOption::ForwardingOff) | Adds a TCP connection with a specific IP address and port number. |
ConnectionResult | add_serial_connection (const std::string & dev_path, int baudrate=DEFAULT_SERIAL_BAUDRATE, bool flow_control=false, ForwardingOption forwarding_option=ForwardingOption::ForwardingOff) | Adds a serial connection with a specific port (COM or UART dev node) and baudrate as specified. |
void | remove_connection (ConnectionHandle 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. |
void | set_system_status (uint8_t system_status) | Set system status of this MAVLink entity. |
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. |
Static Public Attributes
static constexpr auto DEFAULT_UDP_BIND_IP = "0.0.0.0" - Default UDP bind IP (accepts any incoming connections).
static constexpr int DEFAULT_UDP_PORT = 14540 - Default UDP bind port (same port as used by MAVROS).
static constexpr auto DEFAULT_TCP_REMOTE_IP = "127.0.0.1" - Default TCP remote IP (localhost).
static constexpr int DEFAULT_TCP_REMOTE_PORT = 5760 - Default TCP remote port.
static constexpr int DEFAULT_SERIAL_BAUDRATE = 57600 - Default serial baudrate.
static constexpr double DEFAULT_TIMEOUT_S = 0.5 - Default internal timeout in seconds.
Constructor & Destructor Documentation
Mavsdk()
mavsdk::Mavsdk::Mavsdk()=delete
Default constructor without configuration, no longer recommended.
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 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 Enumeration Documentation
enum ComponentType
ComponentType of configurations, used for automatic ID setting.
Value | Description |
---|---|
Autopilot |
SDK is used as an autopilot. |
GroundStation |
SDK is used as a ground station. |
CompanionComputer |
SDK is used as a companion computer on board the MAV. |
Camera |
|
Custom |
SDK is used as a camera. < |
the SDK is used in a custom configuration, no automatic ID will be provided
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: udp://[host][:bind_port]
TCP: tcp://[host][:remote_port]
Serial: serial://dev_node[:baudrate]
For UDP, the host can be set to either:
zero IP: 0.0.0.0 -> behave like a server and listen for heartbeats.
some IP: 192.168.1.12 -> behave like a client, initiate connection and start sending heartbeats.
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: udp://[host][:bind_port]
TCP: tcp://[host][:remote_port]
Serial: serial://dev_node[:baudrate]
For UDP, the host can be set to either:
zero IP: 0.0.0.0 -> behave like a server and listen for heartbeats.
some IP: 192.168.1.12 -> behave like a client, initiate connection and start sending heartbeats.
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.
add_udp_connection()
ConnectionResult mavsdk::Mavsdk::add_udp_connection(int local_port=DEFAULT_UDP_PORT, ForwardingOption forwarding_option=ForwardingOption::ForwardingOff)
Adds a UDP connection to the specified port number.
Any incoming connections are accepted (0.0.0.0).
Parameters
- int local_port - The local UDP port to listen to (defaults to 14540, the same as MAVROS).
- ForwardingOption forwarding_option - message forwarding option (when multiple interfaces are used).
Returns
ConnectionResult - The result of adding the connection.
add_udp_connection()
ConnectionResult mavsdk::Mavsdk::add_udp_connection(const std::string &local_ip, int local_port=DEFAULT_UDP_PORT, ForwardingOption forwarding_option=ForwardingOption::ForwardingOff)
Adds a UDP connection to the specified port number and local interface.
To accept only local connections of the machine, use 127.0.0.1. For any incoming connections, use 0.0.0.0.
Parameters
- const std::string& local_ip - The local UDP IP address to listen to.
- int local_port - The local UDP port to listen to (defaults to 14540, the same as MAVROS).
- ForwardingOption forwarding_option - message forwarding option (when multiple interfaces are used).
Returns
ConnectionResult - The result of adding the connection.
setup_udp_remote()
ConnectionResult mavsdk::Mavsdk::setup_udp_remote(const std::string &remote_ip, int remote_port, ForwardingOption forwarding_option=ForwardingOption::ForwardingOff)
Sets up instance to send heartbeats to the specified remote interface and port number.
Parameters
- const std::string& remote_ip - The remote UDP IP address to report to.
- int remote_port - The local UDP port to report to.
- ForwardingOption forwarding_option - message forwarding option (when multiple interfaces are used).
Returns
ConnectionResult - The result of operation.
add_tcp_connection()
ConnectionResult mavsdk::Mavsdk::add_tcp_connection(const std::string &remote_ip, int remote_port=DEFAULT_TCP_REMOTE_PORT, ForwardingOption forwarding_option=ForwardingOption::ForwardingOff)
Adds a TCP connection with a specific IP address and port number.
Parameters
- const std::string& remote_ip - Remote IP address to connect to.
- int remote_port - The TCP port to connect to (defaults to 5760).
- ForwardingOption forwarding_option - message forwarding option (when multiple interfaces are used).
Returns
ConnectionResult - The result of adding the connection.
add_serial_connection()
ConnectionResult mavsdk::Mavsdk::add_serial_connection(const std::string &dev_path, int baudrate=DEFAULT_SERIAL_BAUDRATE, bool flow_control=false, ForwardingOption forwarding_option=ForwardingOption::ForwardingOff)
Adds a serial connection with a specific port (COM or UART dev node) and baudrate as specified.
Parameters
- const std::string& dev_path - COM or UART dev node name/path (e.g. "/dev/ttyS0", or "COM3" on Windows).
- int baudrate - Baudrate of the serial port (defaults to 57600).
- bool flow_control - enable/disable flow control.
- ForwardingOption forwarding_option - message forwarding option (when multiple interfaces are used).
Returns
ConnectionResult - The result of adding the connection.
remove_connection()
void mavsdk::Mavsdk::remove_connection(ConnectionHandle handle)
Remove connection again.
Parameters
- ConnectionHandle handle - Handle returned when connection was added.
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.
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 -
set_system_status()
void mavsdk::Mavsdk::set_system_status(uint8_t system_status)
Set system status of this MAVLink entity.
The default system status is MAV_STATE_UNINIT.
Parameters
- uint8_t system_status - system status.
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.
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.
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.
Field Documentation
DEFAULT_UDP_BIND_IP
constexpr auto mavsdk::Mavsdk::DEFAULT_UDP_BIND_IP = "0.0.0.0"
Default UDP bind IP (accepts any incoming connections).
DEFAULT_UDP_PORT
constexpr int mavsdk::Mavsdk::DEFAULT_UDP_PORT = 14540
Default UDP bind port (same port as used by MAVROS).
DEFAULT_TCP_REMOTE_IP
constexpr auto mavsdk::Mavsdk::DEFAULT_TCP_REMOTE_IP = "127.0.0.1"
Default TCP remote IP (localhost).
DEFAULT_TCP_REMOTE_PORT
constexpr int mavsdk::Mavsdk::DEFAULT_TCP_REMOTE_PORT = 5760
Default TCP remote port.
DEFAULT_SERIAL_BAUDRATE
constexpr int mavsdk::Mavsdk::DEFAULT_SERIAL_BAUDRATE = 57600
Default serial baudrate.
DEFAULT_TIMEOUT_S
constexpr double mavsdk::Mavsdk::DEFAULT_TIMEOUT_S = 0.5
Default internal timeout in seconds.