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
std::function< void(bool)> IsConnectedCallback type for is connected callback.

Public Member Functions

Type Name Description
  ~System () Destructor.
  System (const System &)=delete Copy constructor (object is not copyable).
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.
DEPRECATED uint64_t get_uuid () const Get the UUID of the system.
uint8_t get_system_id () const MAVLink System ID of connected system.
void subscribe_is_connected (IsConnectedCallback callback) Subscribe to callback to be called when system connection state changes.
void register_component_discovered_callback (discover_callback_t callback)const Register a callback to be called when a component is discovered.
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

Member Typdef Documentation

typedef IsConnectedCallback

using mavsdk::System::IsConnectedCallback =  std::function<void(bool)>

type for is connected callback.

Member Function Documentation

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_uuid()

DEPRECATED uint64_t mavsdk::System::get_uuid() const

Get the UUID of the system.

This method will be deprecated because the UUID will be replaced by a uid with 18 bytes which can be accessed from the info plugin.

Returns

 DEPRECATED uint64_t - UUID of system.

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.

subscribe_is_connected()

void mavsdk::System::subscribe_is_connected(IsConnectedCallback callback)

Subscribe to callback to be called when system connection state changes.

Parameters

register_component_discovered_callback()

void mavsdk::System::register_component_discovered_callback(discover_callback_t callback) const

Register a callback to be called when a component is discovered.

Parameters

  • discover_callback_t callback - a function of type void(ComponentType) which will be called with the component type of the new component.

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

Returns

 const System & -

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

results matching ""

    No results matching ""