mavsdk::Action Class Reference

#include: action.h


Enable simple actions such as arming, taking off, and landing.

Public Types

Type Description
enum OrbitYawBehavior Yaw behaviour during orbit flight.
enum Result Possible results returned for action requests.
std::function< void(Result)> ResultCallback Callback type for asynchronous Action calls.
std::function< void(Result, float)> GetTakeoffAltitudeCallback Callback type for get_takeoff_altitude_async.
std::function< void(Result, float)> GetMaximumSpeedCallback Callback type for get_maximum_speed_async.
std::function< void(Result, float)> GetReturnToLaunchAltitudeCallback Callback type for get_return_to_launch_altitude_async.

Public Member Functions

Type Name Description
  Action (System & system) Constructor. Creates the plugin for a specific System.
  Action (std::shared_ptr< System > system) Constructor. Creates the plugin for a specific System.
  ~Action () override Destructor (internal use only).
  Action (const Action & other) Copy constructor.
void arm_async (const ResultCallback callback) Send command to arm the drone.
Result arm () const Send command to arm the drone.
void disarm_async (const ResultCallback callback) Send command to disarm the drone.
Result disarm () const Send command to disarm the drone.
void takeoff_async (const ResultCallback callback) Send command to take off and hover.
Result takeoff () const Send command to take off and hover.
void land_async (const ResultCallback callback) Send command to land at the current position.
Result land () const Send command to land at the current position.
void reboot_async (const ResultCallback callback) Send command to reboot the drone components.
Result reboot () const Send command to reboot the drone components.
void shutdown_async (const ResultCallback callback) Send command to shut down the drone components.
Result shutdown () const Send command to shut down the drone components.
void terminate_async (const ResultCallback callback) Send command to terminate the drone.
Result terminate () const Send command to terminate the drone.
void kill_async (const ResultCallback callback) Send command to kill the drone.
Result kill () const Send command to kill the drone.
void return_to_launch_async (const ResultCallback callback) Send command to return to the launch (takeoff) position and land.
Result return_to_launch () const Send command to return to the launch (takeoff) position and land.
void goto_location_async (double latitude_deg, double longitude_deg, float absolute_altitude_m, float yaw_deg, const ResultCallback callback) Send command to move the vehicle to a specific global position.
Result goto_location (double latitude_deg, double longitude_deg, float absolute_altitude_m, float yaw_deg)const Send command to move the vehicle to a specific global position.
void do_orbit_async (float radius_m, float velocity_ms, OrbitYawBehavior yaw_behavior, double latitude_deg, double longitude_deg, double absolute_altitude_m, const ResultCallback callback) Send command do orbit to the drone.
Result do_orbit (float radius_m, float velocity_ms, OrbitYawBehavior yaw_behavior, double latitude_deg, double longitude_deg, double absolute_altitude_m)const Send command do orbit to the drone.
void hold_async (const ResultCallback callback) Send command to hold position (a.k.a. "Loiter").
Result hold () const Send command to hold position (a.k.a. "Loiter").
void set_actuator_async (int32_t index, float value, const ResultCallback callback) Send command to set the value of an actuator.
Result set_actuator (int32_t index, float value)const Send command to set the value of an actuator.
void transition_to_fixedwing_async (const ResultCallback callback) Send command to transition the drone to fixedwing.
Result transition_to_fixedwing () const Send command to transition the drone to fixedwing.
void transition_to_multicopter_async (const ResultCallback callback) Send command to transition the drone to multicopter.
Result transition_to_multicopter () const Send command to transition the drone to multicopter.
void get_takeoff_altitude_async (const GetTakeoffAltitudeCallback callback) Get the takeoff altitude (in meters above ground).
std::pair< Result, float > get_takeoff_altitude () const Get the takeoff altitude (in meters above ground).
void set_takeoff_altitude_async (float altitude, const ResultCallback callback) Set takeoff altitude (in meters above ground).
Result set_takeoff_altitude (float altitude)const Set takeoff altitude (in meters above ground).
void get_maximum_speed_async (const GetMaximumSpeedCallback callback) Get the vehicle maximum speed (in metres/second).
std::pair< Result, float > get_maximum_speed () const Get the vehicle maximum speed (in metres/second).
void set_maximum_speed_async (float speed, const ResultCallback callback) Set vehicle maximum speed (in metres/second).
Result set_maximum_speed (float speed)const Set vehicle maximum speed (in metres/second).
void get_return_to_launch_altitude_async (const GetReturnToLaunchAltitudeCallback callback) Get the return to launch minimum return altitude (in meters).
std::pair< Result, float > get_return_to_launch_altitude () const Get the return to launch minimum return altitude (in meters).
void set_return_to_launch_altitude_async (float relative_altitude_m, const ResultCallback callback) Set the return to launch minimum return altitude (in meters).
Result set_return_to_launch_altitude (float relative_altitude_m)const Set the return to launch minimum return altitude (in meters).
void set_current_speed_async (float speed_m_s, const ResultCallback callback) Set current speed.
Result set_current_speed (float speed_m_s)const Set current speed.
const Action & operator= (const Action &)=delete Equality operator (object is not copyable).

Constructor & Destructor Documentation

Action()

mavsdk::Action::Action(System &system)

Constructor. Creates the plugin for a specific System.

The plugin is typically created as shown below:

auto action = Action(system);

Parameters

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

Action()

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

Constructor. Creates the plugin for a specific System.

The plugin is typically created as shown below:

auto action = Action(system);

Parameters

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

~Action()

mavsdk::Action::~Action() override

Destructor (internal use only).

Action()

mavsdk::Action::Action(const Action &other)

Copy constructor.

Parameters

Member Typdef Documentation

typedef ResultCallback

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

Callback type for asynchronous Action calls.

typedef GetTakeoffAltitudeCallback

using mavsdk::Action::GetTakeoffAltitudeCallback =  std::function<void(Result, float)>

Callback type for get_takeoff_altitude_async.

typedef GetMaximumSpeedCallback

using mavsdk::Action::GetMaximumSpeedCallback =  std::function<void(Result, float)>

Callback type for get_maximum_speed_async.

typedef GetReturnToLaunchAltitudeCallback

using mavsdk::Action::GetReturnToLaunchAltitudeCallback =  std::function<void(Result, float)>

Callback type for get_return_to_launch_altitude_async.

Member Enumeration Documentation

enum OrbitYawBehavior

Yaw behaviour during orbit flight.

Value Description
HoldFrontToCircleCenter Vehicle front points to the center (default).
HoldInitialHeading Vehicle front holds heading when message received.
Uncontrolled Yaw uncontrolled.
HoldFrontTangentToCircle Vehicle front follows flight path (tangential to circle).
RcControlled Yaw controlled by RC input.

enum Result

Possible results returned for action 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.
CommandDeniedLandedStateUnknown Command refused because landed state is unknown.
CommandDeniedNotLanded Command refused because vehicle not landed.
Timeout Request timed out.
VtolTransitionSupportUnknown Hybrid/VTOL transition support is unknown.
NoVtolTransitionSupport Vehicle does not support hybrid/VTOL transitions.
ParameterError Error getting or setting parameter.
Unsupported Action not supported.
Failed Action failed.

Member Function Documentation

arm_async()

void mavsdk::Action::arm_async(const ResultCallback callback)

Send command to arm the drone.

Arming a drone normally causes motors to spin at idle. Before arming take all safety precautions and stand clear of the drone!

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

Parameters

arm()

Result mavsdk::Action::arm() const

Send command to arm the drone.

Arming a drone normally causes motors to spin at idle. Before arming take all safety precautions and stand clear of the drone!

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

Returns

Result - Result of request.

disarm_async()

void mavsdk::Action::disarm_async(const ResultCallback callback)

Send command to disarm the drone.

This will disarm a drone that considers itself landed. If flying, the drone should reject the disarm command. Disarming means that all motors will stop.

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

Parameters

disarm()

Result mavsdk::Action::disarm() const

Send command to disarm the drone.

This will disarm a drone that considers itself landed. If flying, the drone should reject the disarm command. Disarming means that all motors will stop.

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

Returns

Result - Result of request.

takeoff_async()

void mavsdk::Action::takeoff_async(const ResultCallback callback)

Send command to take off and hover.

This switches the drone into position control mode and commands it to take off and hover at the takeoff altitude.

Note that the vehicle must be armed before it can take off.

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

Parameters

takeoff()

Result mavsdk::Action::takeoff() const

Send command to take off and hover.

This switches the drone into position control mode and commands it to take off and hover at the takeoff altitude.

Note that the vehicle must be armed before it can take off.

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

Returns

Result - Result of request.

land_async()

void mavsdk::Action::land_async(const ResultCallback callback)

Send command to land at the current position.

This switches the drone to 'Land' flight mode.

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

Parameters

land()

Result mavsdk::Action::land() const

Send command to land at the current position.

This switches the drone to 'Land' flight mode.

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

Returns

Result - Result of request.

reboot_async()

void mavsdk::Action::reboot_async(const ResultCallback callback)

Send command to reboot the drone components.

This will reboot the autopilot, companion computer, camera and gimbal.

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

Parameters

reboot()

Result mavsdk::Action::reboot() const

Send command to reboot the drone components.

This will reboot the autopilot, companion computer, camera and gimbal.

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

Returns

Result - Result of request.

shutdown_async()

void mavsdk::Action::shutdown_async(const ResultCallback callback)

Send command to shut down the drone components.

This will shut down the autopilot, onboard computer, camera and gimbal. This command should only be used when the autopilot is disarmed and autopilots commonly reject it if they are not already ready to shut down.

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

Parameters

shutdown()

Result mavsdk::Action::shutdown() const

Send command to shut down the drone components.

This will shut down the autopilot, onboard computer, camera and gimbal. This command should only be used when the autopilot is disarmed and autopilots commonly reject it if they are not already ready to shut down.

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

Returns

Result - Result of request.

terminate_async()

void mavsdk::Action::terminate_async(const ResultCallback callback)

Send command to terminate the drone.

This will run the terminate routine as configured on the drone (e.g. disarm and open the parachute).

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

Parameters

terminate()

Result mavsdk::Action::terminate() const

Send command to terminate the drone.

This will run the terminate routine as configured on the drone (e.g. disarm and open the parachute).

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

Returns

Result - Result of request.

kill_async()

void mavsdk::Action::kill_async(const ResultCallback callback)

Send command to kill the drone.

This will disarm a drone irrespective of whether it is landed or flying. Note that the drone will fall out of the sky if this command is used while flying.

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

Parameters

kill()

Result mavsdk::Action::kill() const

Send command to kill the drone.

This will disarm a drone irrespective of whether it is landed or flying. Note that the drone will fall out of the sky if this command is used while flying.

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

Returns

Result - Result of request.

return_to_launch_async()

void mavsdk::Action::return_to_launch_async(const ResultCallback callback)

Send command to return to the launch (takeoff) position and land.

This switches the drone into Return mode which generally means it will rise up to a certain altitude to clear any obstacles before heading back to the launch (takeoff) position and land there.

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

Parameters

return_to_launch()

Result mavsdk::Action::return_to_launch() const

Send command to return to the launch (takeoff) position and land.

This switches the drone into Return mode which generally means it will rise up to a certain altitude to clear any obstacles before heading back to the launch (takeoff) position and land there.

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

Returns

Result - Result of request.

goto_location_async()

void mavsdk::Action::goto_location_async(double latitude_deg, double longitude_deg, float absolute_altitude_m, float yaw_deg, const ResultCallback callback)

Send command to move the vehicle to a specific global position.

The latitude and longitude are given in degrees (WGS84 frame) and the altitude in meters AMSL (above mean sea level).

The yaw angle is in degrees (frame is NED, 0 is North, positive is clockwise).

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

Parameters

  • double latitude_deg -
  • double longitude_deg -
  • float absolute_altitude_m -
  • float yaw_deg -
  • const ResultCallback callback -

goto_location()

Result mavsdk::Action::goto_location(double latitude_deg, double longitude_deg, float absolute_altitude_m, float yaw_deg) const

Send command to move the vehicle to a specific global position.

The latitude and longitude are given in degrees (WGS84 frame) and the altitude in meters AMSL (above mean sea level).

The yaw angle is in degrees (frame is NED, 0 is North, positive is clockwise).

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

Parameters

  • double latitude_deg -
  • double longitude_deg -
  • float absolute_altitude_m -
  • float yaw_deg -

Returns

Result - Result of request.

do_orbit_async()

void mavsdk::Action::do_orbit_async(float radius_m, float velocity_ms, OrbitYawBehavior yaw_behavior, double latitude_deg, double longitude_deg, double absolute_altitude_m, const ResultCallback callback)

Send command do orbit to the drone.

This will run the orbit routine with the given parameters.

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

Parameters

  • float radius_m -
  • float velocity_ms -
  • OrbitYawBehavior yaw_behavior -
  • double latitude_deg -
  • double longitude_deg -
  • double absolute_altitude_m -
  • const ResultCallback callback -

do_orbit()

Result mavsdk::Action::do_orbit(float radius_m, float velocity_ms, OrbitYawBehavior yaw_behavior, double latitude_deg, double longitude_deg, double absolute_altitude_m) const

Send command do orbit to the drone.

This will run the orbit routine with the given parameters.

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

Parameters

  • float radius_m -
  • float velocity_ms -
  • OrbitYawBehavior yaw_behavior -
  • double latitude_deg -
  • double longitude_deg -
  • double absolute_altitude_m -

Returns

Result - Result of request.

hold_async()

void mavsdk::Action::hold_async(const ResultCallback callback)

Send command to hold position (a.k.a. "Loiter").

Sends a command to drone to change to Hold flight mode, causing the vehicle to stop and maintain its current GPS position and altitude.

Note: this command is specific to the PX4 Autopilot flight stack as it implies a change to a PX4-specific mode.

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

Parameters

hold()

Result mavsdk::Action::hold() const

Send command to hold position (a.k.a. "Loiter").

Sends a command to drone to change to Hold flight mode, causing the vehicle to stop and maintain its current GPS position and altitude.

Note: this command is specific to the PX4 Autopilot flight stack as it implies a change to a PX4-specific mode.

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

Returns

Result - Result of request.

set_actuator_async()

void mavsdk::Action::set_actuator_async(int32_t index, float value, const ResultCallback callback)

Send command to set the value of an actuator.

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

Parameters

set_actuator()

Result mavsdk::Action::set_actuator(int32_t index, float value) const

Send command to set the value of an actuator.

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

Parameters

  • int32_t index -
  • float value -

Returns

Result - Result of request.

transition_to_fixedwing_async()

void mavsdk::Action::transition_to_fixedwing_async(const ResultCallback callback)

Send command to transition the drone to fixedwing.

The associated action will only be executed for VTOL vehicles (on other vehicle types the command will fail). The command will succeed if called when the vehicle is already in fixedwing mode.

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

Parameters

transition_to_fixedwing()

Result mavsdk::Action::transition_to_fixedwing() const

Send command to transition the drone to fixedwing.

The associated action will only be executed for VTOL vehicles (on other vehicle types the command will fail). The command will succeed if called when the vehicle is already in fixedwing mode.

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

Returns

Result - Result of request.

transition_to_multicopter_async()

void mavsdk::Action::transition_to_multicopter_async(const ResultCallback callback)

Send command to transition the drone to multicopter.

The associated action will only be executed for VTOL vehicles (on other vehicle types the command will fail). The command will succeed if called when the vehicle is already in multicopter mode.

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

Parameters

transition_to_multicopter()

Result mavsdk::Action::transition_to_multicopter() const

Send command to transition the drone to multicopter.

The associated action will only be executed for VTOL vehicles (on other vehicle types the command will fail). The command will succeed if called when the vehicle is already in multicopter mode.

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

Returns

Result - Result of request.

get_takeoff_altitude_async()

void mavsdk::Action::get_takeoff_altitude_async(const GetTakeoffAltitudeCallback callback)

Get the takeoff altitude (in meters above ground).

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

Parameters

get_takeoff_altitude()

std::pair<Result, float> mavsdk::Action::get_takeoff_altitude() const

Get the takeoff altitude (in meters above ground).

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

Returns

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

set_takeoff_altitude_async()

void mavsdk::Action::set_takeoff_altitude_async(float altitude, const ResultCallback callback)

Set takeoff altitude (in meters above ground).

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

Parameters

set_takeoff_altitude()

Result mavsdk::Action::set_takeoff_altitude(float altitude) const

Set takeoff altitude (in meters above ground).

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

Parameters

  • float altitude -

Returns

Result - Result of request.

get_maximum_speed_async()

void mavsdk::Action::get_maximum_speed_async(const GetMaximumSpeedCallback callback)

Get the vehicle maximum speed (in metres/second).

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

Parameters

get_maximum_speed()

std::pair<Result, float> mavsdk::Action::get_maximum_speed() const

Get the vehicle maximum speed (in metres/second).

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

Returns

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

set_maximum_speed_async()

void mavsdk::Action::set_maximum_speed_async(float speed, const ResultCallback callback)

Set vehicle maximum speed (in metres/second).

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

Parameters

set_maximum_speed()

Result mavsdk::Action::set_maximum_speed(float speed) const

Set vehicle maximum speed (in metres/second).

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

Parameters

  • float speed -

Returns

Result - Result of request.

get_return_to_launch_altitude_async()

void mavsdk::Action::get_return_to_launch_altitude_async(const GetReturnToLaunchAltitudeCallback callback)

Get the return to launch minimum return altitude (in meters).

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

Parameters

get_return_to_launch_altitude()

std::pair<Result, float> mavsdk::Action::get_return_to_launch_altitude() const

Get the return to launch minimum return altitude (in meters).

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

Returns

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

set_return_to_launch_altitude_async()

void mavsdk::Action::set_return_to_launch_altitude_async(float relative_altitude_m, const ResultCallback callback)

Set the return to launch minimum return altitude (in meters).

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

Parameters

set_return_to_launch_altitude()

Result mavsdk::Action::set_return_to_launch_altitude(float relative_altitude_m) const

Set the return to launch minimum return altitude (in meters).

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

Parameters

  • float relative_altitude_m -

Returns

Result - Result of request.

set_current_speed_async()

void mavsdk::Action::set_current_speed_async(float speed_m_s, const ResultCallback callback)

Set current speed.

This will set the speed during a mission, reposition, and similar. It is ephemeral, so not stored on the drone and does not survive a reboot.

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

Parameters

set_current_speed()

Result mavsdk::Action::set_current_speed(float speed_m_s) const

Set current speed.

This will set the speed during a mission, reposition, and similar. It is ephemeral, so not stored on the drone and does not survive a reboot.

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

Parameters

  • float speed_m_s -

Returns

Result - Result of request.

operator=()

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

Equality operator (object is not copyable).

Parameters

Returns

 const Action & -

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

results matching ""

    No results matching ""