Calibration

class mavsdk.calibration.Calibration(async_plugin_manager)

Bases: mavsdk._base.AsyncBase

Enable to calibrate sensors of a drone such as gyro, accelerometer, and magnetometer.

Generated by dcsdkgen - MAVSDK Calibration API

calibrate_accelerometer()

Perform accelerometer calibration.

Yields

progress_data (ProgressData) – Progress data

Raises

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

calibrate_gimbal_accelerometer()

Perform gimbal accelerometer calibration.

Yields

progress_data (ProgressData) – Progress data

Raises

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

calibrate_gyro()

Perform gyro calibration.

Yields

progress_data (ProgressData) – Progress data

Raises

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

calibrate_level_horizon()

Perform board level horizon calibration.

Yields

progress_data (ProgressData) – Progress data

Raises

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

calibrate_magnetometer()

Perform magnetometer calibration.

Yields

progress_data (ProgressData) – Progress data

Raises

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

async cancel()

Cancel ongoing calibration process.

Raises

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

name = 'Calibration'
exception mavsdk.calibration.CalibrationError(result, origin, *params)

Bases: Exception

Raised when a CalibrationResult is a fail code

class mavsdk.calibration.CalibrationResult(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.Enum

Possible results returned for calibration commands

UNKNOWN

Unknown result

SUCCESS

The calibration succeeded

NEXT

Intermediate message showing progress or instructions on the next steps

FAILED

Calibration failed

NO_SYSTEM

No system is connected

CONNECTION_ERROR

Connection error

BUSY

Vehicle is busy

COMMAND_DENIED

Command refused by vehicle

TIMEOUT

Command timed out

CANCELLED

Calibration process was cancelled

FAILED_ARMED

Calibration process failed since the vehicle is armed

BUSY = 6
CANCELLED = 9
COMMAND_DENIED = 7
CONNECTION_ERROR = 5
FAILED = 3
FAILED_ARMED = 10
NEXT = 2
NO_SYSTEM = 4
SUCCESS = 1
TIMEOUT = 8
UNKNOWN = 0
class mavsdk.calibration.ProgressData(has_progress, progress, has_status_text, status_text)

Bases: object

Progress data coming from calibration.

Can be a progress percentage, or an instruction text.

Parameters
  • has_progress (bool) – Whether this ProgressData contains a ‘progress’ status or not

  • progress (float) – Progress (percentage)

  • has_status_text (bool) – Whether this ProgressData contains a ‘status_text’ or not

  • status_text (std::string) – Instruction text