Mission¶
- class mavsdk.mission.Mission(async_plugin_manager)¶
Bases:
AsyncBase
Enable waypoint missions.
Generated by dcsdkgen - MAVSDK Mission API
- async cancel_mission_download()¶
Cancel an ongoing mission download.
- Raises:
MissionError – If the request fails. The error contains the reason for the failure.
- async cancel_mission_upload()¶
Cancel an ongoing mission upload.
- Raises:
MissionError – If the request fails. The error contains the reason for the failure.
- async clear_mission()¶
Clear the mission saved on the vehicle.
- Raises:
MissionError – If the request fails. The error contains the reason for the failure.
- async download_mission()¶
Download a list of mission items from the system (asynchronous).
Will fail if any of the downloaded mission items are not supported by the MAVSDK API.
- Returns:
mission_plan – The mission plan
- Return type:
- Raises:
MissionError – If the request fails. The error contains the reason for the failure.
- async download_mission_with_progress()¶
Download a list of mission items from the system (asynchronous) and report progress.
Will fail if any of the downloaded mission items are not supported by the MAVSDK API.
- Yields:
progress_data (ProgressDataOrMission) – The progress data, or the mission plan (when the download is finished)
- Raises:
MissionError – If the request fails. The error contains the reason for the failure.
- async get_return_to_launch_after_mission()¶
Get whether to trigger Return-to-Launch (RTL) after mission is complete.
Before getting this option, it needs to be set, or a mission needs to be downloaded.
- Returns:
enable – If true, trigger an RTL at the end of the mission
- Return type:
bool
- Raises:
MissionError – If the request fails. The error contains the reason for the failure.
- async is_mission_finished()¶
Check if the mission has been finished.
- Returns:
is_finished – True if the mission is finished and the last mission item has been reached
- Return type:
bool
- Raises:
MissionError – If the request fails. The error contains the reason for the failure.
- async mission_progress()¶
Subscribe to mission progress updates.
- Yields:
mission_progress (MissionProgress) – Mission progress
- name = 'Mission'¶
- async pause_mission()¶
Pause the mission.
Pausing the mission puts the vehicle into [HOLD mode](https://docs.px4.io/en/flight_modes/hold.html). A multicopter should just hover at the spot while a fixedwing vehicle should loiter around the location where it paused.
- Raises:
MissionError – If the request fails. The error contains the reason for the failure.
- async set_current_mission_item(index)¶
Sets the mission item index to go to.
By setting the current index to 0, the mission is restarted from the beginning. If it is set to a specific index of a mission item, the mission will be set to this item.
Note that this is not necessarily true for general missions using MAVLink if loop counters are used.
- Parameters:
index (int32_t) – Index of the mission item to be set as the next one (0-based)
- Raises:
MissionError – If the request fails. The error contains the reason for the failure.
- async set_return_to_launch_after_mission(enable)¶
Set whether to trigger Return-to-Launch (RTL) after the mission is complete.
This will only take effect for the next mission upload, meaning that the mission may have to be uploaded again.
- Parameters:
enable (bool) – If true, trigger an RTL at the end of the mission
- Raises:
MissionError – If the request fails. The error contains the reason for the failure.
- async start_mission()¶
Start the mission.
A mission must be uploaded to the vehicle before this can be called.
- Raises:
MissionError – If the request fails. The error contains the reason for the failure.
- async upload_mission(mission_plan)¶
Upload a list of mission items to the system.
The mission items are uploaded to a drone. Once uploaded the mission can be started and executed even if the connection is lost.
- Parameters:
mission_plan (MissionPlan) – The mission plan
- Raises:
MissionError – If the request fails. The error contains the reason for the failure.
- async upload_mission_with_progress(mission_plan)¶
Upload a list of mission items to the system and report upload progress.
The mission items are uploaded to a drone. Once uploaded the mission can be started and executed even if the connection is lost.
- Parameters:
mission_plan (MissionPlan) – The mission plan
- Yields:
progress_data (ProgressData) – The progress data
- Raises:
MissionError – If the request fails. The error contains the reason for the failure.
- exception mavsdk.mission.MissionError(result, origin, *params)¶
Bases:
Exception
Raised when a MissionResult is a fail code
- class mavsdk.mission.MissionItem(latitude_deg, longitude_deg, relative_altitude_m, speed_m_s, is_fly_through, gimbal_pitch_deg, gimbal_yaw_deg, camera_action, loiter_time_s, camera_photo_interval_s, acceptance_radius_m, yaw_deg, camera_photo_distance_m, vehicle_action)¶
Bases:
object
Type representing a mission item.
A MissionItem can contain a position and/or actions. Mission items are building blocks to assemble a mission, which can be sent to (or received from) a system. They cannot be used independently.
- Parameters:
latitude_deg (double) – Latitude in degrees (range: -90 to +90)
longitude_deg (double) – Longitude in degrees (range: -180 to +180)
relative_altitude_m (float) – Altitude relative to takeoff altitude in metres
speed_m_s (float) – Speed to use after this mission item (in metres/second)
is_fly_through (bool) – True will make the drone fly through without stopping, while false will make the drone stop on the waypoint
gimbal_pitch_deg (float) – Gimbal pitch (in degrees)
gimbal_yaw_deg (float) – Gimbal yaw (in degrees)
camera_action (CameraAction) – Camera action to trigger at this mission item
loiter_time_s (float) – Loiter time (in seconds)
camera_photo_interval_s (double) – Camera photo interval to use after this mission item (in seconds)
acceptance_radius_m (float) – Radius for completing a mission item (in metres)
yaw_deg (float) – Absolute yaw angle (in degrees)
camera_photo_distance_m (float) – Camera photo distance to use after this mission item (in meters)
vehicle_action (VehicleAction) – Vehicle action to trigger at this mission item.
- class CameraAction(value)¶
Bases:
Enum
Possible camera actions at a mission item.
Values¶
- NONE
No action
- TAKE_PHOTO
Take a single photo
- START_PHOTO_INTERVAL
Start capturing photos at regular intervals
- STOP_PHOTO_INTERVAL
Stop capturing photos at regular intervals
- START_VIDEO
Start capturing video
- STOP_VIDEO
Stop capturing video
- START_PHOTO_DISTANCE
Start capturing photos at regular distance
- STOP_PHOTO_DISTANCE
Stop capturing photos at regular distance
- NONE = 0¶
- START_PHOTO_DISTANCE = 6¶
- START_PHOTO_INTERVAL = 2¶
- START_VIDEO = 4¶
- STOP_PHOTO_DISTANCE = 7¶
- STOP_PHOTO_INTERVAL = 3¶
- STOP_VIDEO = 5¶
- TAKE_PHOTO = 1¶
- class VehicleAction(value)¶
Bases:
Enum
Possible vehicle actions at a mission item
Values¶
- NONE
No action
- TAKEOFF
Vehicle will takeoff and go to defined waypoint
- LAND
When a waypoint is reached vehicle will land at current position
- TRANSITION_TO_FW
When a waypoint is reached vehicle will transition to fixed-wing mode
- TRANSITION_TO_MC
When a waypoint is reached vehicle will transition to multi-copter mode
- LAND = 2¶
- NONE = 0¶
- TAKEOFF = 1¶
- TRANSITION_TO_FW = 3¶
- TRANSITION_TO_MC = 4¶
- class mavsdk.mission.MissionPlan(mission_items)¶
Bases:
object
Mission plan type
- Parameters:
mission_items ([MissionItem]) – The mission items
- class mavsdk.mission.MissionProgress(current, total)¶
Bases:
object
Mission progress type.
- Parameters:
current (int32_t) – Current mission item index (0-based), if equal to total, the mission is finished
total (int32_t) – Total number of mission items
- class mavsdk.mission.MissionResult(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
Possible results returned for action requests.
Values¶
- UNKNOWN
Unknown result
- SUCCESS
Request succeeded
- ERROR
Error
- TOO_MANY_MISSION_ITEMS
Too many mission items in the mission
- BUSY
Vehicle is busy
- TIMEOUT
Request timed out
- INVALID_ARGUMENT
Invalid argument
- UNSUPPORTED
Mission downloaded from the system is not supported
- NO_MISSION_AVAILABLE
No mission available on the system
- UNSUPPORTED_MISSION_CMD
Unsupported mission command
- TRANSFER_CANCELLED
Mission transfer (upload or download) has been cancelled
- NO_SYSTEM
No system connected
- NEXT
Intermediate message showing progress
- DENIED
Request denied
- PROTOCOL_ERROR
There was a protocol error
- INT_MESSAGES_NOT_SUPPORTED
The system does not support the MISSION_INT protocol
- BUSY = 4¶
- DENIED = 13¶
- ERROR = 2¶
- INT_MESSAGES_NOT_SUPPORTED = 15¶
- INVALID_ARGUMENT = 6¶
- NEXT = 12¶
- NO_MISSION_AVAILABLE = 8¶
- NO_SYSTEM = 11¶
- PROTOCOL_ERROR = 14¶
- SUCCESS = 1¶
- TIMEOUT = 5¶
- TOO_MANY_MISSION_ITEMS = 3¶
- TRANSFER_CANCELLED = 10¶
- UNKNOWN = 0¶
- UNSUPPORTED = 7¶
- UNSUPPORTED_MISSION_CMD = 9¶
- class mavsdk.mission.ProgressData(progress)¶
Bases:
object
Progress data coming from mission upload.
- Parameters:
progress (float) – Progress (0..1.0)
- class mavsdk.mission.ProgressDataOrMission(has_progress, progress, has_mission, mission_plan)¶
Bases:
object
Progress data coming from mission download, or the mission itself (if the transfer succeeds).
- Parameters:
has_progress (bool) – Whether this ProgressData contains a ‘progress’ status or not
progress (float) – Progress (0..1.0)
has_mission (bool) – Whether this ProgressData contains a ‘mission_plan’ or not
mission_plan (MissionPlan) – Mission plan