LogFiles

class mavsdk.log_files.Entry(id, date, size_bytes)

Bases: object

Log file entry type.

Parameters:
  • id (uint32_t) – ID of the log file, to specify a file to be downloaded

  • date (std::string) – Date of the log file in UTC in ISO 8601 format “yyyy-mm-ddThh:mm:ssZ”

  • size_bytes (uint32_t) – Size of file in bytes

class mavsdk.log_files.LogFiles(async_plugin_manager)

Bases: AsyncBase

Allow to download log files from the vehicle after a flight is complete. For log streaming during flight check the logging plugin.

Generated by dcsdkgen - MAVSDK LogFiles API

async download_log_file(entry, path)

Download log file.

Parameters:
  • entry (Entry) – Entry of the log file to download.

  • path (std::string) – Path of where to download log file to.

Yields:

progress (ProgressData) – Progress if result is progress

Raises:

LogFilesError – If the request fails. The error contains the reason for the failure.

async erase_all_log_files()

Erase all log files.

Raises:

LogFilesError – If the request fails. The error contains the reason for the failure.

async get_entries()

Get List of log files.

Returns:

entries – List of entries

Return type:

[Entry]

Raises:

LogFilesError – If the request fails. The error contains the reason for the failure.

name = 'LogFiles'
exception mavsdk.log_files.LogFilesError(result, origin, *params)

Bases: Exception

Raised when a LogFilesResult is a fail code

class mavsdk.log_files.LogFilesResult(result, result_str)

Bases: object

Result type.

Parameters:
  • result (Result) – Result enum value

  • result_str (std::string) – Human-readable English string describing the result

class Result(value)

Bases: Enum

Possible results returned for calibration commands

Values

UNKNOWN

Unknown result

SUCCESS

Request succeeded

NEXT

Progress update

NO_LOGFILES

No log files found

TIMEOUT

A timeout happened

INVALID_ARGUMENT

Invalid argument

FILE_OPEN_FAILED

File open failed

NO_SYSTEM

No system is connected

FILE_OPEN_FAILED = 6
INVALID_ARGUMENT = 5
NEXT = 2
NO_LOGFILES = 3
NO_SYSTEM = 7
SUCCESS = 1
TIMEOUT = 4
UNKNOWN = 0
class mavsdk.log_files.ProgressData(progress)

Bases: object

Progress data coming when downloading a log file.

Parameters:

progress (float) – Progress from 0 to 1