mavsdk::Offboard Class Reference
#include: offboard.h
Control a drone with position, velocity, attitude or motor commands.
The module is called offboard because the 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 sends setpoints at 20Hz (PX4 Offboard mode requires that setpoints are minimally sent at 2Hz).
Data Structures
struct AccelerationNed
struct ActuatorControl
struct ActuatorControlGroup
struct Attitude
struct AttitudeRate
struct PositionGlobalYaw
struct PositionNedYaw
struct VelocityBodyYawspeed
struct VelocityNedYaw
Public Types
Type | Description |
---|---|
enum Result | Possible results returned for offboard requests. |
std::function< void(Result)> ResultCallback | Callback type for asynchronous Offboard calls. |
Public Member Functions
Type | Name | Description |
---|---|---|
Offboard (System & system) | Constructor. Creates the plugin for a specific System. | |
Offboard (std::shared_ptr< System > system) | Constructor. Creates the plugin for a specific System. | |
~Offboard () override | Destructor (internal use only). | |
Offboard (const Offboard & other) | Copy constructor. | |
void | start_async (const ResultCallback callback) | Start offboard control. |
Result | start () const | Start offboard control. |
void | stop_async (const ResultCallback callback) | Stop offboard control. |
Result | stop () const | Stop offboard control. |
bool | is_active () const | Check if offboard control is active. |
Result | set_attitude (Attitude attitude)const | Set the attitude in terms of roll, pitch and yaw in degrees with thrust. |
Result | set_actuator_control (ActuatorControl actuator_control)const | Set direct actuator control values to groups #0 and #1. |
Result | set_attitude_rate (AttitudeRate attitude_rate)const | Set the attitude rate in terms of pitch, roll and yaw angular rate along with thrust. |
Result | set_position_ned (PositionNedYaw position_ned_yaw)const | Set the position in NED coordinates and yaw. |
Result | set_position_global (PositionGlobalYaw position_global_yaw)const | Set the position in Global coordinates (latitude, longitude, altitude) and yaw. |
Result | set_velocity_body (VelocityBodyYawspeed velocity_body_yawspeed)const | Set the velocity in body coordinates and yaw angular rate. Not available for fixed-wing aircraft. |
Result | set_velocity_ned (VelocityNedYaw velocity_ned_yaw)const | Set the velocity in NED coordinates and yaw. Not available for fixed-wing aircraft. |
Result | set_position_velocity_ned (PositionNedYaw position_ned_yaw, VelocityNedYaw velocity_ned_yaw)const | Set the position in NED coordinates, with the velocity to be used as feed-forward. |
Result | set_position_velocity_acceleration_ned (PositionNedYaw position_ned_yaw, VelocityNedYaw velocity_ned_yaw, AccelerationNed acceleration_ned)const | Set the position, velocity and acceleration in NED coordinates, with velocity and acceleration used as feed-forward. |
Result | set_acceleration_ned (AccelerationNed acceleration_ned)const | Set the acceleration in NED coordinates. |
const Offboard & | operator= (const Offboard &)=delete | Equality operator (object is not copyable). |
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 = Offboard(system);
Parameters
- System& system - The specific system associated with this plugin.
Offboard()
mavsdk::Offboard::Offboard(std::shared_ptr< System > system)
Constructor. Creates the plugin for a specific System.
The plugin is typically created as shown below:
auto offboard = Offboard(system);
Parameters
- std::shared_ptr< System > system - The specific system associated with this plugin.
~Offboard()
mavsdk::Offboard::~Offboard() override
Destructor (internal use only).
Offboard()
mavsdk::Offboard::Offboard(const Offboard &other)
Copy constructor.
Parameters
- const Offboard& other -
Member Typdef Documentation
typedef ResultCallback
using mavsdk::Offboard::ResultCallback = std::function<void(Result)>
Callback type for asynchronous Offboard calls.
Member Enumeration Documentation
enum Result
Possible results returned for offboard requests.
Value | Description |
---|---|
Unknown |
Unknown result. |
Success |
Request succeeded. |
NoSystem |
No system is connected. |
ConnectionError |
Connection error. |
Busy |
Vehicle is busy. |
CommandDenied |
Command denied. |
Timeout |
Request timed out. |
NoSetpointSet |
Cannot start without setpoint set. |
Failed |
Request failed. |
Member Function Documentation
start_async()
void mavsdk::Offboard::start_async(const ResultCallback callback)
Start offboard control.
This function is non-blocking. See 'start' for the blocking counterpart.
Parameters
- const ResultCallback callback -
start()
Result mavsdk::Offboard::start() const
Start offboard control.
This function is blocking. See 'start_async' for the non-blocking counterpart.
Returns
Result - Result of request.
stop_async()
void mavsdk::Offboard::stop_async(const ResultCallback callback)
Stop offboard control.
The vehicle will be put into Hold mode: https://docs.px4.io/en/flight_modes/hold.html
This function is non-blocking. See 'stop' for the blocking counterpart.
Parameters
- const ResultCallback callback -
stop()
Result mavsdk::Offboard::stop() const
Stop offboard control.
The vehicle will be put into Hold mode: https://docs.px4.io/en/flight_modes/hold.html
This function is blocking. See 'stop_async' for the non-blocking counterpart.
Returns
Result - Result of request.
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.
This function is blocking.
Returns
bool - Result of request.
set_attitude()
Result mavsdk::Offboard::set_attitude(Attitude attitude) const
Set the attitude in terms of roll, pitch and yaw in degrees with thrust.
This function is blocking.
Parameters
- Attitude attitude -
Returns
Result - Result of request.
set_actuator_control()
Result mavsdk::Offboard::set_actuator_control(ActuatorControl actuator_control) const
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).
This function is blocking.
Parameters
- ActuatorControl actuator_control -
Returns
Result - Result of request.
set_attitude_rate()
Result mavsdk::Offboard::set_attitude_rate(AttitudeRate attitude_rate) const
Set the attitude rate in terms of pitch, roll and yaw angular rate along with thrust.
This function is blocking.
Parameters
- AttitudeRate attitude_rate -
Returns
Result - Result of request.
set_position_ned()
Result mavsdk::Offboard::set_position_ned(PositionNedYaw position_ned_yaw) const
Set the position in NED coordinates and yaw.
This function is blocking.
Parameters
- PositionNedYaw position_ned_yaw -
Returns
Result - Result of request.
set_position_global()
Result mavsdk::Offboard::set_position_global(PositionGlobalYaw position_global_yaw) const
Set the position in Global coordinates (latitude, longitude, altitude) and yaw.
This function is blocking.
Parameters
- PositionGlobalYaw position_global_yaw -
Returns
Result - Result of request.
set_velocity_body()
Result mavsdk::Offboard::set_velocity_body(VelocityBodyYawspeed velocity_body_yawspeed) const
Set the velocity in body coordinates and yaw angular rate. Not available for fixed-wing aircraft.
This function is blocking.
Parameters
- VelocityBodyYawspeed velocity_body_yawspeed -
Returns
Result - Result of request.
set_velocity_ned()
Result mavsdk::Offboard::set_velocity_ned(VelocityNedYaw velocity_ned_yaw) const
Set the velocity in NED coordinates and yaw. Not available for fixed-wing aircraft.
This function is blocking.
Parameters
- VelocityNedYaw velocity_ned_yaw -
Returns
Result - Result of request.
set_position_velocity_ned()
Result mavsdk::Offboard::set_position_velocity_ned(PositionNedYaw position_ned_yaw, VelocityNedYaw velocity_ned_yaw) const
Set the position in NED coordinates, with the velocity to be used as feed-forward.
This function is blocking.
Parameters
- PositionNedYaw position_ned_yaw -
- VelocityNedYaw velocity_ned_yaw -
Returns
Result - Result of request.
set_position_velocity_acceleration_ned()
Result mavsdk::Offboard::set_position_velocity_acceleration_ned(PositionNedYaw position_ned_yaw, VelocityNedYaw velocity_ned_yaw, AccelerationNed acceleration_ned) const
Set the position, velocity and acceleration in NED coordinates, with velocity and acceleration used as feed-forward.
This function is blocking.
Parameters
- PositionNedYaw position_ned_yaw -
- VelocityNedYaw velocity_ned_yaw -
- AccelerationNed acceleration_ned -
Returns
Result - Result of request.
set_acceleration_ned()
Result mavsdk::Offboard::set_acceleration_ned(AccelerationNed acceleration_ned) const
Set the acceleration in NED coordinates.
This function is blocking.
Parameters
- AccelerationNed acceleration_ned -
Returns
Result - Result of request.
operator=()
const Offboard& mavsdk::Offboard::operator=(const Offboard &)=delete
Equality operator (object is not copyable).
Parameters
- const Offboard& -
Returns
const Offboard & -