mavsdk::Param Class Reference

#include: param.h


Provide raw access to get and set parameters.

Data Structures

struct AllParams

struct CustomParam

struct FloatParam

struct IntParam

Public Types

Type Description
enum ProtocolVersion Parameter version.
enum Result Possible results returned for param requests.
std::function< void(Result)> ResultCallback Callback type for asynchronous Param calls.

Public Member Functions

Type Name Description
  Param (System & system) Constructor. Creates the plugin for a specific System.
  Param (std::shared_ptr< System > system) Constructor. Creates the plugin for a specific System.
  ~Param () override Destructor (internal use only).
  Param (const Param & other) Copy constructor.
std::pair< Result, int32_t > get_param_int (std::string name)const Get an int parameter.
Result set_param_int (std::string name, int32_t value)const Set an int parameter.
std::pair< Result, float > get_param_float (std::string name)const Get a float parameter.
Result set_param_float (std::string name, float value)const Set a float parameter.
std::pair< Result, std::string > get_param_custom (std::string name)const Get a custom parameter.
Result set_param_custom (std::string name, std::string value)const Set a custom parameter.
Param::AllParams get_all_params () const Get all parameters.
Result select_component (int32_t component_id, ProtocolVersion protocol_version)const Select component ID of parameter component to talk to and param protocol version.
const Param & operator= (const Param &)=delete Equality operator (object is not copyable).

Constructor & Destructor Documentation

Param()

mavsdk::Param::Param(System &system)

Constructor. Creates the plugin for a specific System.

The plugin is typically created as shown below:

auto param = Param(system);

Parameters

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

Param()

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

Constructor. Creates the plugin for a specific System.

The plugin is typically created as shown below:

auto param = Param(system);

Parameters

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

~Param()

mavsdk::Param::~Param() override

Destructor (internal use only).

Param()

mavsdk::Param::Param(const Param &other)

Copy constructor.

Parameters

Member Typdef Documentation

typedef ResultCallback

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

Callback type for asynchronous Param calls.

Member Enumeration Documentation

enum ProtocolVersion

Parameter version.

Value Description
V1 Original v1 version.
Ext Extended param version.

enum Result

Possible results returned for param requests.

Value Description
Unknown Unknown result.
Success Request succeeded.
Timeout Request timed out.
ConnectionError Connection error.
WrongType Wrong type.
ParamNameTooLong Parameter name too long (> 16).
NoSystem No system connected.
ParamValueTooLong Param value too long (> 128).
Failed Operation failed..

Member Function Documentation

get_param_int()

std::pair<Result, int32_t> mavsdk::Param::get_param_int(std::string name) const

Get an int parameter.

If the type is wrong, the result will be WRONG_TYPE.

This function is blocking.

Parameters

  • std::string name -

Returns

 std::pair< Result, int32_t > - Result of request.

set_param_int()

Result mavsdk::Param::set_param_int(std::string name, int32_t value) const

Set an int parameter.

If the type is wrong, the result will be WRONG_TYPE.

This function is blocking.

Parameters

  • std::string name -
  • int32_t value -

Returns

Result - Result of request.

get_param_float()

std::pair<Result, float> mavsdk::Param::get_param_float(std::string name) const

Get a float parameter.

If the type is wrong, the result will be WRONG_TYPE.

This function is blocking.

Parameters

  • std::string name -

Returns

 std::pair< Result, float > - Result of request.

set_param_float()

Result mavsdk::Param::set_param_float(std::string name, float value) const

Set a float parameter.

If the type is wrong, the result will be WRONG_TYPE.

This function is blocking.

Parameters

  • std::string name -
  • float value -

Returns

Result - Result of request.

get_param_custom()

std::pair<Result, std::string> mavsdk::Param::get_param_custom(std::string name) const

Get a custom parameter.

If the type is wrong, the result will be WRONG_TYPE.

This function is blocking.

Parameters

  • std::string name -

Returns

 std::pair< Result, std::string > - Result of request.

set_param_custom()

Result mavsdk::Param::set_param_custom(std::string name, std::string value) const

Set a custom parameter.

If the type is wrong, the result will be WRONG_TYPE.

This function is blocking.

Parameters

  • std::string name -
  • std::string value -

Returns

Result - Result of request.

get_all_params()

Param::AllParams mavsdk::Param::get_all_params() const

Get all parameters.

This function is blocking.

Returns

Param::AllParams - Result of request.

select_component()

Result mavsdk::Param::select_component(int32_t component_id, ProtocolVersion protocol_version) const

Select component ID of parameter component to talk to and param protocol version.

Default is the autopilot component (1), and Version (0).

This function is blocking.

Parameters

Returns

Result - Result of request.

operator=()

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

Equality operator (object is not copyable).

Parameters

Returns

 const Param & -

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

results matching ""

    No results matching ""