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 |
---|---|
std::function< void()> NewSystemCallback | Callback type discover and timeout notifications. |
Public Member Functions
Type | Name | Description |
---|---|---|
Mavsdk () | Constructor. | |
~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. |
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. |
std::vector< std::shared_ptr< System > > | systems () const | Get a vector of systems which have been discovered or set-up. |
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. |
void | subscribe_on_new_system (const NewSystemCallback & callback) | Get notification about a change in systems. |
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()
Constructor.
~Mavsdk()
mavsdk::Mavsdk::~Mavsdk()
Destructor.
Disconnects all connected vehicles and releases all resources.
Member Typdef Documentation
typedef NewSystemCallback
using mavsdk::Mavsdk::NewSystemCallback = std::function<void()>
Callback type discover and timeout notifications.
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_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.
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.
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()
void mavsdk::Mavsdk::subscribe_on_new_system(const NewSystemCallback &callback)
Get notification about a change in systems.
This gets called whenever a system is added.
Only one subscriber is possible at any time. On a second subscription, the previous one is overwritten. To unsubscribe, pass nullptr;
Parameters
- const NewSystemCallback& callback - Callback to subscribe.
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.