mavsdk::Calibration Class Reference

#include: calibration.h


Enable 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(Result)> ResultCallback Callback type for asynchronous Calibration calls.
std::function< void(Result, ProgressData)> CalibrateGyroCallback Callback type for calibrate_gyro_async.
std::function< void(Result, ProgressData)> CalibrateAccelerometerCallback Callback type for calibrate_accelerometer_async.
std::function< void(Result, ProgressData)> CalibrateMagnetometerCallback Callback type for calibrate_magnetometer_async.
std::function< void(Result, ProgressData)> CalibrateLevelHorizonCallback Callback type for calibrate_level_horizon_async.
std::function< void(Result, ProgressData)> CalibrateGimbalAccelerometerCallback Callback type for calibrate_gimbal_accelerometer_async.

Public Member Functions

Type Name Description
  Calibration (System & system) Constructor. Creates the plugin for a specific System.
  Calibration (std::shared_ptr< System > system) Constructor. Creates the plugin for a specific System.
  ~Calibration () override Destructor (internal use only).
  Calibration (const Calibration & other) Copy constructor.
void calibrate_gyro_async (const CalibrateGyroCallback & callback) Perform gyro calibration.
void calibrate_accelerometer_async (const CalibrateAccelerometerCallback & callback) Perform accelerometer calibration.
void calibrate_magnetometer_async (const CalibrateMagnetometerCallback & callback) Perform magnetometer calibration.
void calibrate_level_horizon_async (const CalibrateLevelHorizonCallback & callback) Perform board level horizon calibration.
void calibrate_gimbal_accelerometer_async (const CalibrateGimbalAccelerometerCallback & callback) Perform gimbal accelerometer calibration.
Result cancel () const Cancel ongoing calibration process.
const Calibration & operator= (const Calibration &)=delete Equality operator (object is not copyable).

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 = Calibration(system);

Parameters

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

Calibration()

mavsdk::Calibration::Calibration(std::shared_ptr< System > system)

Constructor. Creates the plugin for a specific System.

The plugin is typically created as shown below:

auto calibration = Calibration(system);

Parameters

  • std::shared_ptr< System > system - The specific system associated with this plugin.

~Calibration()

mavsdk::Calibration::~Calibration() override

Destructor (internal use only).

Calibration()

mavsdk::Calibration::Calibration(const Calibration &other)

Copy constructor.

Parameters

Member Typdef Documentation

typedef ResultCallback

using mavsdk::Calibration::ResultCallback =  std::function<void(Result)>

Callback type for asynchronous Calibration calls.

typedef CalibrateGyroCallback

using mavsdk::Calibration::CalibrateGyroCallback =  std::function<void(Result, ProgressData)>

Callback type for calibrate_gyro_async.

typedef CalibrateAccelerometerCallback

using mavsdk::Calibration::CalibrateAccelerometerCallback =  std::function<void(Result, ProgressData)>

Callback type for calibrate_accelerometer_async.

typedef CalibrateMagnetometerCallback

using mavsdk::Calibration::CalibrateMagnetometerCallback =  std::function<void(Result, ProgressData)>

Callback type for calibrate_magnetometer_async.

typedef CalibrateLevelHorizonCallback

using mavsdk::Calibration::CalibrateLevelHorizonCallback =  std::function<void(Result, ProgressData)>

Callback type for calibrate_level_horizon_async.

typedef CalibrateGimbalAccelerometerCallback

using mavsdk::Calibration::CalibrateGimbalAccelerometerCallback =  std::function<void(Result, ProgressData)>

Callback type for calibrate_gimbal_accelerometer_async.

Member Enumeration Documentation

enum Result

Possible results returned for calibration commands.

Value Description
Unknown Unknown result.
Success The calibration succeeded.
Next Intermediate message showing progress or instructions on the next steps.
Failed Calibration failed.
NoSystem No system is connected.
ConnectionError Connection error.
Busy Vehicle is busy.
CommandDenied Command refused by vehicle.
Timeout Command timed out.
Cancelled Calibration process was cancelled.
FailedArmed Calibration process failed since the vehicle is armed.
Unsupported Functionality not supported.

Member Function Documentation

calibrate_gyro_async()

void mavsdk::Calibration::calibrate_gyro_async(const CalibrateGyroCallback &callback)

Perform gyro calibration.

Parameters

calibrate_accelerometer_async()

void mavsdk::Calibration::calibrate_accelerometer_async(const CalibrateAccelerometerCallback &callback)

Perform accelerometer calibration.

Parameters

calibrate_magnetometer_async()

void mavsdk::Calibration::calibrate_magnetometer_async(const CalibrateMagnetometerCallback &callback)

Perform magnetometer calibration.

Parameters

calibrate_level_horizon_async()

void mavsdk::Calibration::calibrate_level_horizon_async(const CalibrateLevelHorizonCallback &callback)

Perform board level horizon calibration.

Parameters

calibrate_gimbal_accelerometer_async()

void mavsdk::Calibration::calibrate_gimbal_accelerometer_async(const CalibrateGimbalAccelerometerCallback &callback)

Perform gimbal accelerometer calibration.

Parameters

cancel()

Result mavsdk::Calibration::cancel() const

Cancel ongoing calibration process.

This function is blocking.

Returns

Result - Result of request.

operator=()

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

Equality operator (object is not copyable).

Parameters

Returns

 const Calibration & -

© MAVSDK Development Team 2017-2023. License: CC BY 4.0            Updated: 2023-12-27 03:10:20

results matching ""

    No results matching ""