mavsdk::ManualControl Class Reference

#include: manual_control.h


Enable manual control using e.g. a joystick or gamepad.

Public Types

Type Description
enum Result Possible results returned for manual control requests.
std::function< void(Result)> ResultCallback Callback type for asynchronous ManualControl calls.

Public Member Functions

Type Name Description
  ManualControl (System & system) Constructor. Creates the plugin for a specific System.
  ManualControl (std::shared_ptr< System > system) Constructor. Creates the plugin for a specific System.
  ~ManualControl () override Destructor (internal use only).
  ManualControl (const ManualControl & other) Copy constructor.
void start_position_control_async (const ResultCallback callback) Start position control using e.g. joystick input.
Result start_position_control () const Start position control using e.g. joystick input.
void start_altitude_control_async (const ResultCallback callback) Start altitude control.
Result start_altitude_control () const Start altitude control.
Result set_manual_control_input (float x, float y, float z, float r)const Set manual control input.
const ManualControl & operator= (const ManualControl &)=delete Equality operator (object is not copyable).

Constructor & Destructor Documentation

ManualControl()

mavsdk::ManualControl::ManualControl(System &system)

Constructor. Creates the plugin for a specific System.

The plugin is typically created as shown below:

auto manual_control = ManualControl(system);

Parameters

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

ManualControl()

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

Constructor. Creates the plugin for a specific System.

The plugin is typically created as shown below:

auto manual_control = ManualControl(system);

Parameters

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

~ManualControl()

mavsdk::ManualControl::~ManualControl() override

Destructor (internal use only).

ManualControl()

mavsdk::ManualControl::ManualControl(const ManualControl &other)

Copy constructor.

Parameters

Member Typdef Documentation

typedef ResultCallback

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

Callback type for asynchronous ManualControl calls.

Member Enumeration Documentation

enum Result

Possible results returned for manual control requests.

Value Description
Unknown Unknown result.
Success Request was successful.
NoSystem No system is connected.
ConnectionError Connection error.
Busy Vehicle is busy.
CommandDenied Command refused by vehicle.
Timeout Request timed out.
InputOutOfRange Input out of range.
InputNotSet No Input set.

Member Function Documentation

start_position_control_async()

void mavsdk::ManualControl::start_position_control_async(const ResultCallback callback)

Start position control using e.g. joystick input.

Requires manual control input to be sent regularly already. Requires a valid position using e.g. GPS, external vision, or optical flow.

This function is non-blocking. See 'start_position_control' for the blocking counterpart.

Parameters

start_position_control()

Result mavsdk::ManualControl::start_position_control() const

Start position control using e.g. joystick input.

Requires manual control input to be sent regularly already. Requires a valid position using e.g. GPS, external vision, or optical flow.

This function is blocking. See 'start_position_control_async' for the non-blocking counterpart.

Returns

Result - Result of request.

start_altitude_control_async()

void mavsdk::ManualControl::start_altitude_control_async(const ResultCallback callback)

Start altitude control.

Requires manual control input to be sent regularly already. Does not require a valid position e.g. GPS.

This function is non-blocking. See 'start_altitude_control' for the blocking counterpart.

Parameters

start_altitude_control()

Result mavsdk::ManualControl::start_altitude_control() const

Start altitude control.

Requires manual control input to be sent regularly already. Does not require a valid position e.g. GPS.

This function is blocking. See 'start_altitude_control_async' for the non-blocking counterpart.

Returns

Result - Result of request.

set_manual_control_input()

Result mavsdk::ManualControl::set_manual_control_input(float x, float y, float z, float r) const

Set manual control input.

The manual control input needs to be sent at a rate high enough to prevent triggering of RC loss, a good minimum rate is 10 Hz.

This function is blocking.

Parameters

  • float x -
  • float y -
  • float z -
  • float r -

Returns

Result - Result of request.

operator=()

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

Equality operator (object is not copyable).

Parameters

Returns

 const ManualControl & -

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

results matching ""

    No results matching ""