mavsdk::Mocap Class Reference

#include: mocap.h


This class allows users to get vehicle mocap and state information (e.g. battery, GPS, RC connection, flight mode etc.) and set mocap update rates.

Data Structures

struct AngleBody

struct AngularVelocityBody

struct AttitudePositionMocap

struct Odometry

struct PositionBody

struct Quaternion

struct SpeedBody

struct VisionPositionEstimate

Public Types

Type Description
enum Result Results enum for mocap requests.
std::array< float, 21 > Covariance Covariance type.

Public Member Functions

Type Name Description
  Mocap (System & system) Constructor. Creates the plugin for a specific System.
  ~Mocap () Destructor (internal use only).
  Mocap (const Mocap &)=delete Copy constructor (object is not copyable).
Result set_vision_position_estimate (VisionPositionEstimate vision_position_estimate) Set the vision position.
Result set_attitude_position_mocap (AttitudePositionMocap attitude_position_mocap) Set the motion capture attitude and position.
Result set_odometry (const Odometry & odometry) Set the Odometry information.
const Mocap & operator= (const Mocap &)=delete Equality operator (object is not copyable).

Static Public Member Functions

Type Name Description
const char * result_str (Result result) Get human-readable English string for Mocap::Result.

Constructor & Destructor Documentation

Mocap()

mavsdk::Mocap::Mocap(System &system)

Constructor. Creates the plugin for a specific System.

The plugin is typically created as shown below:

auto mocap = std::make_shared<Mocap>(system);

Parameters

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

~Mocap()

mavsdk::Mocap::~Mocap()

Destructor (internal use only).

Mocap()

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

Copy constructor (object is not copyable).

Parameters

Member Typdef Documentation

typedef Covariance

typedef std::array<float, 21> mavsdk::Mocap::Covariance

Covariance type.

Member Enumeration Documentation

enum Result

Results enum for mocap requests.

Value Description
UNKNOWN Unknown error.
SUCCESS Request succeeded.
NO_SYSTEM No system connected.
CONNECTION_ERROR Connection error.
INVALID_REQUEST_DATA Invalid request data.

Member Function Documentation

set_vision_position_estimate()

Result mavsdk::Mocap::set_vision_position_estimate(VisionPositionEstimate vision_position_estimate)

Set the vision position.

Parameters

  • VisionPositionEstimate vision_position_estimate - Position struct. Set time_usec to 0 to use internal timestamp.

Returns

Result -

set_attitude_position_mocap()

Result mavsdk::Mocap::set_attitude_position_mocap(AttitudePositionMocap attitude_position_mocap)

Set the motion capture attitude and position.

Parameters

  • AttitudePositionMocap attitude_position_mocap - Position struct. Set time_usec to 0 to use internal timestamp.

Returns

Result -

set_odometry()

Result mavsdk::Mocap::set_odometry(const Odometry &odometry)

Set the Odometry information.

Parameters

  • const Odometry& odometry - Odometry struct. Set time_usec to 0 to use internal timestamp.

Returns

Result -

operator=()

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

Equality operator (object is not copyable).

Parameters

Returns

 const Mocap & -

result_str()

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

Get human-readable English string for Mocap::Result.

Parameters

  • Result result - The enum value for which string is needed.

Returns

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

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

results matching ""

    No results matching ""