Action¶
-
class
mavsdk.action.
Action
(async_plugin_manager)¶ Bases:
mavsdk._base.AsyncBase
Enable simple actions such as arming, taking off, and landing.
Generated by dcsdkgen - MAVSDK Action API
-
async
arm
()¶ 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!
- Raises
ActionError – If the request fails. The error contains the reason for the failure.
-
async
disarm
()¶ 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.
- Raises
ActionError – If the request fails. The error contains the reason for the failure.
-
async
do_orbit
(radius_m, velocity_ms, yaw_behavior, latitude_deg, longitude_deg, absolute_altitude_m)¶ Send command do orbit to the drone.
This will run the orbit routine with the given parameters.
- Parameters
radius_m (float) – Radius of circle (in meters)
velocity_ms (float) – Tangential velocity (in m/s)
yaw_behavior (OrbitYawBehavior) – Yaw behavior of vehicle (ORBIT_YAW_BEHAVIOUR)
latitude_deg (double) – Center point latitude in degrees. NAN: use current latitude for center
longitude_deg (double) – Center point longitude in degrees. NAN: use current longitude for center
absolute_altitude_m (double) – Center point altitude in meters. NAN: use current altitude for center
- Raises
ActionError – If the request fails. The error contains the reason for the failure.
-
async
get_maximum_speed
()¶ Get the vehicle maximum speed (in metres/second).
- Returns
speed – Maximum speed (in metres/second)
- Return type
float
- Raises
ActionError – If the request fails. The error contains the reason for the failure.
-
async
get_return_to_launch_altitude
()¶ Get the return to launch minimum return altitude (in meters).
- Returns
relative_altitude_m – Return altitude relative to takeoff location (in meters)
- Return type
float
- Raises
ActionError – If the request fails. The error contains the reason for the failure.
-
async
get_takeoff_altitude
()¶ Get the takeoff altitude (in meters above ground).
- Returns
altitude – Takeoff altitude relative to ground/takeoff location (in meters)
- Return type
float
- Raises
ActionError – If the request fails. The error contains the reason for the failure.
-
async
goto_location
(latitude_deg, longitude_deg, absolute_altitude_m, 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).
The yaw angle is in degrees (frame is NED, 0 is North, positive is clockwise).
- Parameters
latitude_deg (double) – Latitude (in degrees)
longitude_deg (double) – Longitude (in degrees)
absolute_altitude_m (float) – Altitude AMSL (in meters)
yaw_deg (float) – Yaw angle (in degrees, frame is NED, 0 is North, positive is clockwise)
- Raises
ActionError – If the request fails. The error contains the reason for the failure.
-
async
kill
()¶ 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.
- Raises
ActionError – If the request fails. The error contains the reason for the failure.
-
async
land
()¶ Send command to land at the current position.
This switches the drone to ‘Land’ flight mode.
- Raises
ActionError – If the request fails. The error contains the reason for the failure.
-
name
= 'Action'¶
-
async
reboot
()¶ Send command to reboot the drone components.
This will reboot the autopilot, companion computer, camera and gimbal.
- Raises
ActionError – If the request fails. The error contains the reason for the failure.
-
async
return_to_launch
()¶ Send command to return to the launch (takeoff) position and land.
This switches the drone into [Return mode](https://docs.px4.io/master/en/flight_modes/return.html) 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.
- Raises
ActionError – If the request fails. The error contains the reason for the failure.
-
async
set_maximum_speed
(speed)¶ Set vehicle maximum speed (in metres/second).
- Parameters
speed (float) – Maximum speed (in metres/second)
- Raises
ActionError – If the request fails. The error contains the reason for the failure.
-
async
set_return_to_launch_altitude
(relative_altitude_m)¶ Set the return to launch minimum return altitude (in meters).
- Parameters
relative_altitude_m (float) – Return altitude relative to takeoff location (in meters)
- Raises
ActionError – If the request fails. The error contains the reason for the failure.
-
async
set_takeoff_altitude
(altitude)¶ Set takeoff altitude (in meters above ground).
- Parameters
altitude (float) – Takeoff altitude relative to ground/takeoff location (in meters)
- Raises
ActionError – If the request fails. The error contains the reason for the failure.
-
async
shutdown
()¶ 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.
- Raises
ActionError – If the request fails. The error contains the reason for the failure.
-
async
takeoff
()¶ 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.
- Raises
ActionError – If the request fails. The error contains the reason for the failure.
-
async
terminate
()¶ Send command to terminate the drone.
This will run the terminate routine as configured on the drone (e.g. disarm and open the parachute).
- Raises
ActionError – If the request fails. The error contains the reason for the failure.
-
async
transition_to_fixedwing
()¶ 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.
- Raises
ActionError – If the request fails. The error contains the reason for the failure.
-
async
transition_to_multicopter
()¶ 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.
- Raises
ActionError – If the request fails. The error contains the reason for the failure.
-
async
-
exception
mavsdk.action.
ActionError
(result, origin, *params)¶ Bases:
Exception
Raised when a ActionResult is a fail code
-
class
mavsdk.action.
ActionResult
(result, result_str)¶ Bases:
object
Result type.
- Parameters
result (Result) – Result enum value
result_str (std::string) – Human-readable English string describing the result
-
class
Result
(value)¶ Bases:
enum.Enum
Possible results returned for action requests.
- UNKNOWN
Unknown result
- SUCCESS
Request was successful
- NO_SYSTEM
No system is connected
- CONNECTION_ERROR
Connection error
- BUSY
Vehicle is busy
- 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
Request timed out
- VTOL_TRANSITION_SUPPORT_UNKNOWN
Hybrid/VTOL transition support is unknown
- NO_VTOL_TRANSITION_SUPPORT
Vehicle does not support hybrid/VTOL transitions
- PARAMETER_ERROR
Error getting or setting parameter
-
BUSY
= 4¶
-
COMMAND_DENIED
= 5¶
-
COMMAND_DENIED_LANDED_STATE_UNKNOWN
= 6¶
-
COMMAND_DENIED_NOT_LANDED
= 7¶
-
CONNECTION_ERROR
= 3¶
-
NO_SYSTEM
= 2¶
-
NO_VTOL_TRANSITION_SUPPORT
= 10¶
-
PARAMETER_ERROR
= 11¶
-
SUCCESS
= 1¶
-
TIMEOUT
= 8¶
-
UNKNOWN
= 0¶
-
VTOL_TRANSITION_SUPPORT_UNKNOWN
= 9¶
-
class
mavsdk.action.
OrbitYawBehavior
(value)¶ Bases:
enum.Enum
Yaw behaviour during orbit flight.
- HOLD_FRONT_TO_CIRCLE_CENTER
Vehicle front points to the center (default)
- HOLD_INITIAL_HEADING
Vehicle front holds heading when message received
- UNCONTROLLED
Yaw uncontrolled
- HOLD_FRONT_TANGENT_TO_CIRCLE
Vehicle front follows flight path (tangential to circle)
- RC_CONTROLLED
Yaw controlled by RC input
-
HOLD_FRONT_TANGENT_TO_CIRCLE
= 3¶
-
HOLD_FRONT_TO_CIRCLE_CENTER
= 0¶
-
HOLD_INITIAL_HEADING
= 1¶
-
RC_CONTROLLED
= 4¶
-
UNCONTROLLED
= 2¶