mavsdk::Action Class Reference
#include: action.h
The Action class enables simple actions for a drone such as arming, taking off, and landing.
Synchronous and asynchronous variants of the action methods are supplied.
The action methods send their associated MAVLink commands to the vehicle and complete (return synchronously or callback asynchronously) with an Action::Result value indicating whether the vehicle has accepted or rejected the command, or that there has been some error. If the command is accepted, the vehicle will then start to perform the associated action.
Public Types
Type | Description |
---|---|
enum Result | Possible results returned for commanded actions. |
std::function< void(Result)> result_callback_t | Callback type for asynchronous Action calls. |
Public Member Functions
Type | Name | Description |
---|---|---|
Action (System & system) | Constructor. Creates the plugin for a specific System. | |
~Action () | Destructor (internal use only). | |
Action (const Action &)=delete | Copy constructor (object is not copyable). | |
Result | arm () const | Send command to arm the drone (synchronous). |
Result | disarm () const | Send command to disarm the drone (synchronous). |
Result | kill () const | Send command to kill the drone (synchronous). |
Action::Result | reboot () const | Send command to reboot the drone components. |
Result | takeoff () const | Send command to take off and hover (synchronous). |
Result | land () const | Send command to land at the current position (synchronous). |
Result | return_to_launch () const | Send command to return to the launch (takeoff) position and land (asynchronous). |
Result | goto_location (double latitude_deg, double longitude_deg, float altitude_amsl_m, float yaw_deg) | Send command to move the vehicle to a specific global position. |
Result | transition_to_fixedwing () const | Send command to transition the drone to fixedwing. |
Result | transition_to_multicopter () const | Send command to transition the drone to multicopter. |
void | arm_async (result_callback_t callback) | Send command to arm the drone (asynchronous). |
void | disarm_async (result_callback_t callback) | Send command to disarm the drone (asynchronous). |
void | kill_async (result_callback_t callback) | Send command to kill the drone (asynchronous). |
void | takeoff_async (result_callback_t callback) | Send command to take off and hover (asynchronous). |
void | land_async (result_callback_t callback) | Send command to land at the current position (asynchronous). |
void | return_to_launch_async (result_callback_t callback) | Send command to return to the launch (takeoff) position and land (asynchronous). |
void | transition_to_fixedwing_async (result_callback_t callback) | Send command to transition the drone to fixedwing (asynchronous). |
void | transition_to_multicopter_async (result_callback_t callback) | Send command to transition the drone to multicopter (asynchronous). |
Result | set_takeoff_altitude (float relative_altitude_m) | Set takeoff altitude above ground. |
std::pair< Result, float > | get_takeoff_altitude () const | Get the takeoff altitude. |
Result | set_max_speed (float speed_m_s) | Set vehicle maximum speed. |
std::pair< Result, float > | get_max_speed () const | Get the vehicle maximum speed. |
Result | set_return_to_launch_return_altitude (float relative_altitude_m) | Set the return to launch minimum return altitude. |
std::pair< Result, float > | get_return_to_launch_return_altitude () const | Get the return to launch minimum return altitude. |
const Action & | operator= (const Action &)=delete | Equality operator (object is not copyable). |
Static Public Member Functions
Type | Name | Description |
---|---|---|
const char * | result_str (Result result) | Returns a human-readable English string for an Result. |
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 = std::make_shared<Action>(system);
Parameters
- System& system - The specific system associated with this plugin.
~Action()
mavsdk::Action::~Action()
Destructor (internal use only).
Action()
mavsdk::Action::Action(const Action &)=delete
Copy constructor (object is not copyable).
Parameters
- const Action& -
Member Typdef Documentation
typedef result_callback_t
typedef std::function<void(Result)> mavsdk::Action::result_callback_t
Callback type for asynchronous Action calls.
Member Enumeration Documentation
enum Result
Possible results returned for commanded actions.
Mavsdk does not throw exceptions. Instead a result of this type will be returned when you execute actions.
Value | Description |
---|---|
UNKNOWN |
Unspecified error. |
SUCCESS |
Success. The action command was accepted by the vehicle. |
NO_SYSTEM |
No system is connected error. |
CONNECTION_ERROR |
Connection error. |
BUSY |
Vehicle busy error. |
COMMAND_DENIED |
Command refused by vehicle. |
COMMAND_DENIED_LANDED_STATE_UNKNOWN |
Command refused because landed state is unknown. |
COMMAND_DENIED_NOT_LANDED |
Command refused because vehicle not landed. |
TIMEOUT |
Timeout waiting for command acknowledgement from vehicle. |
VTOL_TRANSITION_SUPPORT_UNKNOWN |
hybrid/VTOL transition refused because VTOL support is unknown. |
NO_VTOL_TRANSITION_SUPPORT |
Vehicle does not support hybrid/VTOL transitions. |
PARAMETER_ERROR |
Error getting or setting parameter. |
Member Function Documentation
arm()
Result mavsdk::Action::arm() const
Send command to arm the drone (synchronous).
Arming a drone normally causes motors to spin at idle. Before arming take all safety precautions and stand clear of the drone!
Returns
Result - Result of request.
disarm()
Result mavsdk::Action::disarm() const
Send command to disarm the drone (synchronous).
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.
Returns
Result - Result of request.
kill()
Result mavsdk::Action::kill() const
Send command to kill the drone (synchronous).
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.
Returns
Result - Result of request.
reboot()
Action::Result mavsdk::Action::reboot() const
Send command to reboot the drone components.
This will reboot the autopilot, onboard computer, camera and gimbal.
Returns
Action::Result - Action::Result of request.
takeoff()
Result mavsdk::Action::takeoff() const
Send command to take off and hover (synchronous).
This switches the drone into position control mode and commands it to take off and hover at the takeoff altitude (set using set_takeoff_altitude()).
Note that the vehicle must be armed before it can take off.
Returns
Result - Result of request.
land()
Result mavsdk::Action::land() const
Send command to land at the current position (synchronous).
This switches the drone to Land mode.
Returns
Result - Result of request.
return_to_launch()
Result mavsdk::Action::return_to_launch() const
Send command to return to the launch (takeoff) position and land (asynchronous).
This switches the drone into RTL 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.
Returns
Result - Result of request.
goto_location()
Result mavsdk::Action::goto_location(double latitude_deg, double longitude_deg, float altitude_amsl_m, float yaw_deg)
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).
Parameters
- double latitude_deg - Latitude in degrees.
- double longitude_deg - Longitude in degrees.
- float altitude_amsl_m - Altitude AMSL in meters.
- float yaw_deg - Yaw angle in degrees (Frame is NED, 0 is North, positive is clockwise).
Returns
Result - Result of request.
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 with an Result). The command will succeed if called when the vehicle is already in fixedwing mode.
Returns
Result - Result of request.
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 with an Result). The command will succeed if called when the vehicle is already in multicopter mode.
Returns
Result - Result of request.
arm_async()
void mavsdk::Action::arm_async(result_callback_t callback)
Send command to arm the drone (asynchronous).
Note that arming a drone normally means that the motors will spin at idle. Therefore, before arming take all safety precautions and stand clear of the drone.
Parameters
- result_callback_t callback - Function to call with result of request.
disarm_async()
void mavsdk::Action::disarm_async(result_callback_t callback)
Send command to disarm the drone (asynchronous).
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.
Parameters
- result_callback_t callback - Function to call with result of request.
kill_async()
void mavsdk::Action::kill_async(result_callback_t callback)
Send command to kill the drone (asynchronous).
This will disarm a drone irrespective of whether it is landed or flying. Note that the drone will fall out of the sky if you use this command while flying.
Parameters
- result_callback_t callback - Function to call with result of request.
takeoff_async()
void mavsdk::Action::takeoff_async(result_callback_t callback)
Send command to take off and hover (asynchronous).
This switches the drone into position control mode and commands it to take off and hover at the takeoff altitude set using set_takeoff_altitude().
Note that the vehicle must be armed before it can take off.
Parameters
- result_callback_t callback - Function to call with result of request
land_async()
void mavsdk::Action::land_async(result_callback_t callback)
Send command to land at the current position (asynchronous).
This switches the drone to Land mode.
Parameters
- result_callback_t callback - Function to call with result of request.
return_to_launch_async()
void mavsdk::Action::return_to_launch_async(result_callback_t callback)
Send command to return to the launch (takeoff) position and land (asynchronous).
This switches the drone into RTL 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.
Parameters
- result_callback_t callback - Function to call with result of request.
transition_to_fixedwing_async()
void mavsdk::Action::transition_to_fixedwing_async(result_callback_t callback)
Send command to transition the drone to fixedwing (asynchronous).
The associated action will only be executed for VTOL vehicles (on other vehicle types the command will fail with an Result). The command will succeed if called when the vehicle is already in fixedwing mode.
Parameters
- result_callback_t callback - Function to call with result of request.
transition_to_multicopter_async()
void mavsdk::Action::transition_to_multicopter_async(result_callback_t callback)
Send command to transition the drone to multicopter (asynchronous).
The associated action will only be executed for VTOL vehicles (on other vehicle types the command will fail with an Result). The command will succeed if called when the vehicle is already in multicopter mode.
Parameters
- result_callback_t callback - Function to call with result of request.
set_takeoff_altitude()
Result mavsdk::Action::set_takeoff_altitude(float relative_altitude_m)
Set takeoff altitude above ground.
Parameters
- float relative_altitude_m - Takeoff altitude relative to takeoff location, in meters.
Returns
Result - Result of request.
get_takeoff_altitude()
std::pair<Result, float> mavsdk::Action::get_takeoff_altitude() const
Get the takeoff altitude.
Returns
std::pair< Result, float > - A pair containing the result of request and if successful, the takeoff altitude relative to ground/takeoff location, in meters.
set_max_speed()
Result mavsdk::Action::set_max_speed(float speed_m_s)
Set vehicle maximum speed.
Parameters
- float speed_m_s - Maximum speed in metres/second.
Returns
Result - Result of request.
get_max_speed()
std::pair<Result, float> mavsdk::Action::get_max_speed() const
Get the vehicle maximum speed.
Returns
std::pair< Result, float > - A pair containing the result of the request and if successful, the maximum speed in metres/second.
set_return_to_launch_return_altitude()
Result mavsdk::Action::set_return_to_launch_return_altitude(float relative_altitude_m)
Set the return to launch minimum return altitude.
When return to launch is initiated, the vehicle climbs to the return altitude if it is lower and stays at the current altitude if higher than the return altitude. Then it returns to the home location and lands there.
Parameters
- float relative_altitude_m - Return altitude relative to takeoff location, in meters.
Returns
Result - Result of request.
get_return_to_launch_return_altitude()
std::pair<Result, float> mavsdk::Action::get_return_to_launch_return_altitude() const
Get the return to launch minimum return altitude.
Returns
std::pair< Result, float > - A pair containing the result of the request and if successful, the return altitude relative to takeoff location, in meters.
See Also:
operator=()
const Action& mavsdk::Action::operator=(const Action &)=delete
Equality operator (object is not copyable).
Parameters
- const Action& -
Returns
const Action & -
result_str()
static const char* mavsdk::Action::result_str(Result result)
Returns a human-readable English string for an Result.
Parameters
- Result result - The enum value for which a human readable string is required.
Returns
const char * - Human readable string for the Result.