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.
std::function< void(uint64_t uuid)> event_callback_t Callback type for discover and timeout notifications (deprecated).

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) Adds Connection via URL.
ConnectionResult add_udp_connection (int local_port=DEFAULT_UDP_PORT) Adds a UDP connection to the specified port number.
ConnectionResult add_udp_connection (const std::string & local_ip, int local_port=DEFAULT_UDP_PORT) Adds a UDP connection to the specified port number and local interface.
ConnectionResult setup_udp_remote (const std::string & remote_ip, int remote_port) Sets up instance to send heartbeats to the specified remote interface and port number.
ConnectionResult add_tcp_connection (int remote_port=DEFAULT_TCP_REMOTE_PORT) Adds a TCP connection with a specific port number on localhost.
ConnectionResult add_tcp_connection (const std::string & remote_ip, int remote_port=DEFAULT_TCP_REMOTE_PORT) 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) 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.
DEPRECATED std::vector< uint64_t > system_uuids () const Get vector of system UUIDs (deprecated).
DEPRECATED System & system () const Get the first discovered system.
DEPRECATED System & system (uint64_t uuid)const Get the system with the specified UUID (deprecated).
void subscribe_on_new_system (NewSystemCallback callback) Get notification about a change in systems.
DEPRECATED bool is_connected () const Returns true if exactly one system is currently connected.
DEPRECATED bool is_connected (uint64_t uuid)const Returns true if a system is currently connected (deprecated).
DEPRECATED void register_on_discover (event_callback_t callback) Register callback for system discovery.
DEPRECATED void register_on_timeout (event_callback_t callback) Register callback for system timeout.

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.

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.

typedef event_callback_t

typedef std::function<void(uint64_t uuid)> mavsdk::Mavsdk::event_callback_t

Callback type for discover and timeout notifications (deprecated).

This typedef is deprecated because the UUID is replaced by uid with 18 bytes.

Parameters

  • uuid - UUID of system (or MAVLink system ID for systems that don't have a UUID).

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)

Adds Connection via URL.

Supports connection: Serial, TCP or UDP. Connection URL format should be:

  • UDP - udp://[Bind_host][:Bind_port]

  • TCP - tcp://[Remote_host][:Remote_port]

  • Serial - serial://Dev_Node[:Baudrate]

Parameters

  • const std::string& connection_url - connection URL string.

Returns

ConnectionResult - The result of adding the connection.

add_udp_connection()

ConnectionResult mavsdk::Mavsdk::add_udp_connection(int local_port=DEFAULT_UDP_PORT)

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).

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)

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).

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)

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.

Returns

ConnectionResult - The result of operation.

add_tcp_connection()

ConnectionResult mavsdk::Mavsdk::add_tcp_connection(int remote_port=DEFAULT_TCP_REMOTE_PORT)

Adds a TCP connection with a specific port number on localhost.

Parameters

  • int remote_port - The TCP port to connect to (defaults to 5760).

Returns

ConnectionResult - The result of adding the connection.

add_tcp_connection()

ConnectionResult mavsdk::Mavsdk::add_tcp_connection(const std::string &remote_ip, int remote_port=DEFAULT_TCP_REMOTE_PORT)

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).

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)

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

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

system_uuids()

DEPRECATED std::vector<uint64_t> mavsdk::Mavsdk::system_uuids() const

Get vector of system UUIDs (deprecated).

This returns a vector of the UUIDs of all systems that have been discovered. If a system doesn't have a UUID then Mavsdk will instead use its MAVLink system ID (range: 0..255).

This method will be deprecated because the UUID will be replaced by a uid with 18 bytes.

Returns

 DEPRECATED std::vector< uint64_t > - A vector containing the UUIDs.

system()

DEPRECATED System& mavsdk::Mavsdk::system() const

Get the first discovered system.

This returns the first discovered system or a null system if no system has yet been found.

This method will be deprecated because it will be replaced by a vector of system pointers.

Returns

 DEPRECATED System & - A reference to a system.

system()

DEPRECATED System& mavsdk::Mavsdk::system(uint64_t uuid) const

Get the system with the specified UUID (deprecated).

This returns a system for a given UUID if such a system has been discovered and a null system otherwise.

This method will be deprecated because the UUID will be replaced by a uid with 18 bytes.

Parameters

  • uint64_t uuid - UUID of system to get.

Returns

 DEPRECATED System & - A reference to the specified system.

subscribe_on_new_system()

void mavsdk::Mavsdk::subscribe_on_new_system(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

is_connected()

DEPRECATED bool mavsdk::Mavsdk::is_connected() const

Returns true if exactly one system is currently connected.

Connected means we are receiving heartbeats from this system. It means the same as "discovered" and "not timed out".

If multiple systems have connected, this will return false.

This method will be deprecated because is_connected will be a method of the system, not of mavsdk.

Returns

 DEPRECATED bool - true if exactly one system is connected.

is_connected()

DEPRECATED bool mavsdk::Mavsdk::is_connected(uint64_t uuid) const

Returns true if a system is currently connected (deprecated).

Connected means we are receiving heartbeats from this system. It means the same as "discovered" and "not timed out".

This method will be deprecated because the UUID will be replaced by uid with 18 bytes.

Parameters

  • uint64_t uuid - UUID of system to check.

Returns

 DEPRECATED bool - true if system is connected.

register_on_discover()

DEPRECATED void mavsdk::Mavsdk::register_on_discover(event_callback_t callback)

Register callback for system discovery.

This sets a callback that will be notified if a new system is discovered.

If systems have been discovered before this callback is registered, they will be notified at the time this callback is registered.

Only one callback can be registered at a time. If this function is called several times, previous callbacks will be overwritten.

Note This method will be deprecated because event_callback_t is deprecated and it will be replaced by subscribe_on_new_system().

Parameters

Returns

 DEPRECATED void -

register_on_timeout()

DEPRECATED void mavsdk::Mavsdk::register_on_timeout(event_callback_t callback)

Register callback for system timeout.

This sets a callback that will be notified if no heartbeat of the system has been received in 3 seconds.

Only one callback can be registered at a time. If this function is called several times, previous callbacks will be overwritten.

Note This method will be deprecated because event_callback_t is deprecated and it will be replaced by subscribe_on_new_system().

Parameters

Returns

 DEPRECATED void -

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.

© Dronecode 2017-2020. License: CC BY 4.0            Updated: 2021-02-08 13:41:53

results matching ""

    No results matching ""