mavsdk::Calibration Class Reference

#include: calibration.h


The Calibration class enables to calibrate sensors of a drone such as gyro, accelerometer, and magnetometer.

Data Structures

struct ProgressData

Public Types

Type Description
enum Result Possible results returned for calibration commands.
std::function< void(const Result result, const ProgressData)> calibration_callback_t Callback type for asynchronous calibration call.

Public Member Functions

Type Name Description
  Calibration (System & system) Constructor. Creates the plugin for a specific System.
  ~Calibration () Destructor (internal use only).
  Calibration (const Calibration &)=delete Copy constructor (object is not copyable).
void calibrate_gyro_async (calibration_callback_t callback) Perform gyro calibration (asynchronous call).
void calibrate_accelerometer_async (calibration_callback_t callback) Perform accelerometer calibration (asynchronous call).
void calibrate_magnetometer_async (calibration_callback_t callback) Perform magnetometer calibration (asynchronous call).
void calibrate_gimbal_accelerometer_async (calibration_callback_t callback) Perform gimbal accelerometer calibration (asynchronous call).
void cancel_calibration () Cancel ongoing calibration.
const Calibration & operator= (const Calibration &)=delete Equality operator (object is not copyable).

Static Public Member Functions

Type Name Description
const char * result_str (Result result) Returns a human-readable English string for Calibration::Result.

Constructor & Destructor Documentation

Calibration()

mavsdk::Calibration::Calibration(System &system)

Constructor. Creates the plugin for a specific System.

The plugin is typically created as shown below:

auto calibration = std::make_shared<Calibration>(system);

Parameters

  • System& system - The specific system associated with this plugin.

~Calibration()

mavsdk::Calibration::~Calibration()

Destructor (internal use only).

Calibration()

mavsdk::Calibration::Calibration(const Calibration &)=delete

Copy constructor (object is not copyable).

Parameters

Member Typdef Documentation

typedef calibration_callback_t

typedef std::function<void(const Result result, const ProgressData)> mavsdk::Calibration::calibration_callback_t

Callback type for asynchronous calibration call.

Member Enumeration Documentation

enum Result

Possible results returned for calibration commands.

Value Description
UNKNOWN
SUCCESS
IN_PROGRESS
INSTRUCTION
FAILED
NO_SYSTEM
CONNECTION_ERROR
BUSY
COMMAND_DENIED
TIMEOUT
CANCELLED

Member Function Documentation

calibrate_gyro_async()

void mavsdk::Calibration::calibrate_gyro_async(calibration_callback_t callback)

Perform gyro calibration (asynchronous call).

Parameters

calibrate_accelerometer_async()

void mavsdk::Calibration::calibrate_accelerometer_async(calibration_callback_t callback)

Perform accelerometer calibration (asynchronous call).

Parameters

calibrate_magnetometer_async()

void mavsdk::Calibration::calibrate_magnetometer_async(calibration_callback_t callback)

Perform magnetometer calibration (asynchronous call).

Parameters

calibrate_gimbal_accelerometer_async()

void mavsdk::Calibration::calibrate_gimbal_accelerometer_async(calibration_callback_t callback)

Perform gimbal accelerometer calibration (asynchronous call).

Parameters

cancel_calibration()

void mavsdk::Calibration::cancel_calibration()

Cancel ongoing calibration.

operator=()

const Calibration& mavsdk::Calibration::operator=(const Calibration &)=delete

Equality operator (object is not copyable).

Parameters

Returns

 const Calibration & -

result_str()

static const char* mavsdk::Calibration::result_str(Result result)

Returns a human-readable English string for Calibration::Result.

Parameters

  • Result result - The enum value for which a human readable string is required.

Returns

 const char * - Human readable string for the Calibration::Result.

© Dronecode 2017-2019. License: CC BY 4.0            Updated: 2019-11-05 22:27:07

results matching ""

    No results matching ""