MissionRaw

class mavsdk.mission_raw.MissionImportData(mission_items, geofence_items, rally_items)

Bases: object

Mission import data

Parameters:
class mavsdk.mission_raw.MissionItem(seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z, mission_type)

Bases: object

Mission item exactly identical to MAVLink MISSION_ITEM_INT.

Parameters:
  • seq (uint32_t) – Sequence (uint16_t)

  • frame (uint32_t) – The coordinate system of the waypoint (actually uint8_t)

  • command (uint32_t) – The scheduled action for the waypoint (actually uint16_t)

  • current (uint32_t) – false:0, true:1 (actually uint8_t)

  • autocontinue (uint32_t) – Autocontinue to next waypoint (actually uint8_t)

  • param1 (float) – PARAM1, see MAV_CMD enum

  • param2 (float) – PARAM2, see MAV_CMD enum

  • param3 (float) – PARAM3, see MAV_CMD enum

  • param4 (float) – PARAM4, see MAV_CMD enum

  • x (int32_t) – PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7

  • y (int32_t) – PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7

  • z (float) – PARAM7 / local: Z coordinate, global: altitude (relative or absolute, depending on frame)

  • mission_type (uint32_t) – Mission type (actually uint8_t)

class mavsdk.mission_raw.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_raw.MissionRaw(async_plugin_manager)

Bases: AsyncBase

Enable raw missions as exposed by MAVLink.

Generated by dcsdkgen - MAVSDK MissionRaw API

async cancel_mission_download()

Cancel an ongoing mission download.

Raises:

MissionRawError – If the request fails. The error contains the reason for the failure.

async cancel_mission_upload()

Cancel an ongoing mission upload.

Raises:

MissionRawError – If the request fails. The error contains the reason for the failure.

async clear_mission()

Clear the mission saved on the vehicle.

Raises:

MissionRawError – If the request fails. The error contains the reason for the failure.

async download_mission()

Download a list of raw mission items from the system (asynchronous).

Returns:

mission_items – The mission items

Return type:

[MissionItem]

Raises:

MissionRawError – If the request fails. The error contains the reason for the failure.

async import_qgroundcontrol_mission(qgc_plan_path)

Import a QGroundControl missions in JSON .plan format, from a file.

Supported: - Waypoints - Survey Not supported: - Structure Scan

Parameters:

qgc_plan_path (std::string) – File path of the QGC plan

Returns:

mission_import_data – The imported mission data

Return type:

MissionImportData

Raises:

MissionRawError – If the request fails. The error contains the reason for the failure.

async import_qgroundcontrol_mission_from_string(qgc_plan)

Import a QGroundControl missions in JSON .plan format, from a string.

Supported: - Waypoints - Survey Not supported: - Structure Scan

Parameters:

qgc_plan (std::string) – QGC plan as string

Returns:

mission_import_data – The imported mission data

Return type:

MissionImportData

Raises:

MissionRawError – If the request fails. The error contains the reason for the failure.

async mission_changed()

Subscribes to mission changed.

This notification can be used to be informed if a ground station has been uploaded or changed by a ground station or companion computer.

@param callback Callback to notify about change.

Yields:

mission_changed (bool) – Mission has changed

async mission_progress()

Subscribe to mission progress updates.

Yields:

mission_progress (MissionProgress) – Mission progress

name = 'MissionRaw'
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:

MissionRawError – If the request fails. The error contains the reason for the failure.

async set_current_mission_item(index)

Sets the raw 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 raw mission item, the mission will be set to this item.

Parameters:

index (int32_t) – Index of the mission item to be set as the next one (0-based)

Raises:

MissionRawError – 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:

MissionRawError – If the request fails. The error contains the reason for the failure.

async upload_geofence(mission_items)

Upload a list of geofence items to the system.

Parameters:

mission_items ([MissionItem]) – The mission items

Raises:

MissionRawError – If the request fails. The error contains the reason for the failure.

async upload_mission(mission_items)

Upload a list of raw mission items to the system.

The raw mission items are uploaded to a drone. Once uploaded the mission can be started and executed even if the connection is lost.

Parameters:

mission_items ([MissionItem]) – The mission items

Raises:

MissionRawError – If the request fails. The error contains the reason for the failure.

async upload_rally_points(mission_items)

Upload a list of rally point items to the system.

Parameters:

mission_items ([MissionItem]) – The mission items

Raises:

MissionRawError – If the request fails. The error contains the reason for the failure.

exception mavsdk.mission_raw.MissionRawError(result, origin, *params)

Bases: Exception

Raised when a MissionRawResult is a fail code

class mavsdk.mission_raw.MissionRawResult(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

TRANSFER_CANCELLED

Mission transfer (upload or download) has been cancelled

FAILED_TO_OPEN_QGC_PLAN

Failed to open the QGroundControl plan

FAILED_TO_PARSE_QGC_PLAN

Failed to parse the QGroundControl plan

NO_SYSTEM

No system connected

DENIED

Request denied

MISSION_TYPE_NOT_CONSISTENT

Mission type is not consistent

INVALID_SEQUENCE

The mission item sequences are not increasing correctly

CURRENT_INVALID

The current item is not set correctly

PROTOCOL_ERROR

There was a protocol error

INT_MESSAGES_NOT_SUPPORTED

The system does not support the MISSION_INT protocol

BUSY = 4
CURRENT_INVALID = 16
DENIED = 13
ERROR = 2
FAILED_TO_OPEN_QGC_PLAN = 10
FAILED_TO_PARSE_QGC_PLAN = 11
INT_MESSAGES_NOT_SUPPORTED = 18
INVALID_ARGUMENT = 6
INVALID_SEQUENCE = 15
MISSION_TYPE_NOT_CONSISTENT = 14
NO_MISSION_AVAILABLE = 8
NO_SYSTEM = 12
PROTOCOL_ERROR = 17
SUCCESS = 1
TIMEOUT = 5
TOO_MANY_MISSION_ITEMS = 3
TRANSFER_CANCELLED = 9
UNKNOWN = 0
UNSUPPORTED = 7