mavsdk::Offboard Class Reference

#include: offboard.h


This class is used to control a drone with velocity commands.

The module is called offboard because the velocity commands can be sent from external sources as opposed to onboard control right inside the autopilot "board".

Client code must specify a setpoint before starting offboard mode. Mavsdk automatically resends setpoints at 20Hz (PX4 Offboard mode requires that setpoints are minimally resent at 2Hz). If more precise control is required, clients can call the setpoint methods at whatever rate is required.

Attention: this is work in progress, use with caution!

Data Structures

struct ActuatorControl

struct Attitude

struct AttitudeRate

struct PositionNEDYaw

struct VelocityBodyYawspeed

struct VelocityNEDYaw

Public Types

Type Description
enum Result Results for offboard requests.
std::function< void(Result)> result_callback_t Callback type for offboard requests.

Public Member Functions

Type Name Description
  Offboard (System & system) Constructor. Creates the plugin for a specific System.
  ~Offboard () Destructor (internal use only).
  Offboard (const Offboard &)=delete Copy constructor (object is not copyable).
Offboard::Result start () Start offboard control (synchronous).
Offboard::Result stop () Stop offboard control (synchronous).
void start_async (result_callback_t callback) Start offboard control (asynchronous).
void stop_async (result_callback_t callback) Stop offboard control (asynchronous).
bool is_active () const Check if offboard control is active.
void set_position_ned (PositionNEDYaw position_ned_yaw) Set the position in NED coordinates and yaw.
void set_velocity_ned (VelocityNEDYaw velocity_ned_yaw) Set the velocity in NED coordinates and yaw.
void set_velocity_body (VelocityBodyYawspeed velocity_body_yawspeed) Set the velocity body coordinates and yaw angular rate.
void set_attitude (Attitude attitude) Set the attitude in terms of roll, pitch and yaw in degrees with thrust in percentage.
void set_attitude_rate (AttitudeRate attitude_rate) Set the attitude rate in terms of pitch, roll and yaw angular rate along with thrust in percentage.
void set_actuator_control (const ActuatorControl actuator_control) Set direct actuator control values to groups #0 and #1. First 8 controls will go to control group 0, the following 8 controls to control group 1 (if actuator_control.num_controls more than 8).
const Offboard & operator= (const Offboard &)=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 Offboard::Result.

Constructor & Destructor Documentation

Offboard()

mavsdk::Offboard::Offboard(System &system)

Constructor. Creates the plugin for a specific System.

The plugin is typically created as shown below:

auto offboard = std::make_shared<Offboard>(system);

Parameters

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

~Offboard()

mavsdk::Offboard::~Offboard()

Destructor (internal use only).

Offboard()

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

Copy constructor (object is not copyable).

Parameters

Member Typdef Documentation

typedef result_callback_t

typedef std::function<void(Result)> mavsdk::Offboard::result_callback_t

Callback type for offboard requests.

Member Enumeration Documentation

enum Result

Results for offboard requests.

Value Description
UNKNOWN Unknown error.
SUCCESS Request succeeded.
NO_SYSTEM No system connected.
CONNECTION_ERROR Connection error.
BUSY Vehicle busy.
COMMAND_DENIED Command denied.
TIMEOUT Request timeout.
NO_SETPOINT_SET Can't start without setpoint set.

Member Function Documentation

start()

Offboard::Result mavsdk::Offboard::start()

Start offboard control (synchronous).

Attention: this is work in progress, use with caution!

Returns

Offboard::Result - Result of request.

stop()

Offboard::Result mavsdk::Offboard::stop()

Stop offboard control (synchronous).

The vehicle will be put into Hold mode: https://docs.px4.io/en/flight_modes/hold.html

Returns

Offboard::Result - Result of request.

start_async()

void mavsdk::Offboard::start_async(result_callback_t callback)

Start offboard control (asynchronous).

Attention: This is work in progress, use with caution!

Parameters

stop_async()

void mavsdk::Offboard::stop_async(result_callback_t callback)

Stop offboard control (asynchronous).

The vehicle will be put into Hold mode: https://docs.px4.io/en/flight_modes/hold.html

Parameters

is_active()

bool mavsdk::Offboard::is_active() const

Check if offboard control is active.

true means that the vehicle is in offboard mode and we are actively sending setpoints.

Returns

 bool - true if active

set_position_ned()

void mavsdk::Offboard::set_position_ned(PositionNEDYaw position_ned_yaw)

Set the position in NED coordinates and yaw.

Parameters

set_velocity_ned()

void mavsdk::Offboard::set_velocity_ned(VelocityNEDYaw velocity_ned_yaw)

Set the velocity in NED coordinates and yaw.

Parameters

set_velocity_body()

void mavsdk::Offboard::set_velocity_body(VelocityBodyYawspeed velocity_body_yawspeed)

Set the velocity body coordinates and yaw angular rate.

Parameters

set_attitude()

void mavsdk::Offboard::set_attitude(Attitude attitude)

Set the attitude in terms of roll, pitch and yaw in degrees with thrust in percentage.

Parameters

  • Attitude attitude - roll, pitch and yaw in degrees along with thrust in percentage.

set_attitude_rate()

void mavsdk::Offboard::set_attitude_rate(AttitudeRate attitude_rate)

Set the attitude rate in terms of pitch, roll and yaw angular rate along with thrust in percentage.

Parameters

  • AttitudeRate attitude_rate - roll, pitch and yaw angular rate along with thrust in percentage.

set_actuator_control()

void mavsdk::Offboard::set_actuator_control(const ActuatorControl actuator_control)

Set direct actuator control values to groups #0 and #1. First 8 controls will go to control group 0, the following 8 controls to control group 1 (if actuator_control.num_controls more than 8).

Parameters

operator=()

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

Equality operator (object is not copyable).

Parameters

Returns

 const Offboard & -

result_str()

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

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

Parameters

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

Returns

 const char * - Human-readable string for enum value.

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

results matching ""

    No results matching ""