Mission feature#

command message olympe.messages.mission.activate(uid, _timeout=10, _no_expect=False, _float_tol=(1e-07, 1e-09))#

mission.activate

Tells the drone to start the mission. The mission will start only if there is no missing_requirements and if it was previously loaded (.idle state).

Parameters:
  • uid (string) – Unique id of the mission

  • _timeout (int) – command message timeout (defaults to 10)

  • _no_expect (bool) – if True for,do not expect the usual command expectation (defaults to False)

  • _float_tol (tuple) – specify the float comparison tolerance, a 2-tuple containing a relative tolerance float value and an absolute tolerate float value (default to (1e-07, 1e-09)). See python 3 stdlib math.isclose documentation for more information

Supported by:

ANAFI Ai:

with an up to date firmware

Result: The drone sends state().

Expectations: state(uid=self.uid, state='active', _policy='wait')

event message olympe.messages.mission.capabilities(uid=None, name=None, desc=None, version=None, recipient_id=None, target_model_id=None, target_min_version=None, target_max_version=None, list_flags=None, _policy='check_wait', _float_tol=(1e-07, 1e-09))#

mission.capabilities

Missions capabilities.

Parameters:
  • uid (string) – Unique id of the mission

  • name (string) – Name of the mission.

  • desc (string) – Description of the mission.

  • version (string) – Version of the mission.

  • recipient_id (u16) – Id to use to exchange messages with the mission (given by the drone)

  • target_model_id (u16) – Model id of the supported target.

  • target_min_version (string) – Minimum version of target firmware supported.

  • target_max_version (string) – Maximum version of target firmware supported.

  • list_flags (BitfieldOf(olympe.enums.mission.list_flags, u8)) –

  • _policy (olympe.arsdkng.expectations.ExpectPolicy) – specify how to check the expectation. Possible values are ‘check’, ‘wait’ and ‘check_wait’ (defaults to ‘check_wait’)

  • _float_tol (tuple) – specify the float comparison tolerance, a 2-tuple containing a relative tolerance float value and an absolute tolerate float value (default to (1e-07, 1e-09)). See python 3 stdlib math.isclose documentation for more information

Supported by:

ANAFI Ai:

with an up to date firmware

Triggered At connection.

command message olympe.messages.mission.custom_cmd(recipient_id, service_id, msg_num, payload, _timeout=10, _no_expect=False, _float_tol=(1e-07, 1e-09))#

mission.custom_cmd

Parameters:
  • recipient_id (u16) –

  • service_id (u16) –

  • msg_num (u16) –

  • payload (binary) –

  • _timeout (int) – command message timeout (defaults to 10)

  • _no_expect (bool) – if True for,do not expect the usual command expectation (defaults to False)

  • _float_tol (tuple) – specify the float comparison tolerance, a 2-tuple containing a relative tolerance float value and an absolute tolerate float value (default to (1e-07, 1e-09)). See python 3 stdlib math.isclose documentation for more information

Supported by:

ANAFI Ai:

with an up to date firmware

event message olympe.messages.mission.custom_evt(recipient_id=None, service_id=None, msg_num=None, payload=None, _policy='check_wait', _float_tol=(1e-07, 1e-09))#

mission.custom_evt

Parameters:
  • recipient_id (u16) –

  • service_id (u16) –

  • msg_num (u16) –

  • payload (binary) –

  • _policy (olympe.arsdkng.expectations.ExpectPolicy) – specify how to check the expectation. Possible values are ‘check’, ‘wait’ and ‘check_wait’ (defaults to ‘check_wait’)

  • _float_tol (tuple) – specify the float comparison tolerance, a 2-tuple containing a relative tolerance float value and an absolute tolerate float value (default to (1e-07, 1e-09)). See python 3 stdlib math.isclose documentation for more information

Supported by:

ANAFI Ai:

with an up to date firmware

command message olympe.messages.mission.custom_msg_disable(_timeout=10, _no_expect=False, _float_tol=(1e-07, 1e-09))#

mission.custom_msg_disable

Disable custom messages for all missions.

Parameters:
  • _timeout (int) – command message timeout (defaults to 10)

  • _no_expect (bool) – if True for,do not expect the usual command expectation (defaults to False)

  • _float_tol (tuple) – specify the float comparison tolerance, a 2-tuple containing a relative tolerance float value and an absolute tolerate float value (default to (1e-07, 1e-09)). See python 3 stdlib math.isclose documentation for more information

Supported by:

ANAFI Ai:

with an up to date firmware

command message olympe.messages.mission.custom_msg_enable(_timeout=10, _no_expect=False, _float_tol=(1e-07, 1e-09))#

mission.custom_msg_enable

Enable custom messages for all missions.

Parameters:
  • _timeout (int) – command message timeout (defaults to 10)

  • _no_expect (bool) – if True for,do not expect the usual command expectation (defaults to False)

  • _float_tol (tuple) – specify the float comparison tolerance, a 2-tuple containing a relative tolerance float value and an absolute tolerate float value (default to (1e-07, 1e-09)). See python 3 stdlib math.isclose documentation for more information

Supported by:

ANAFI Ai:

with an up to date firmware

command message olympe.messages.mission.load(uid, _timeout=10, _no_expect=False, _float_tol=(1e-07, 1e-09))#

mission.load

Tells the drone to load the corresponding mission.

Parameters:
  • uid (string) – Unique id of the mission

  • _timeout (int) – command message timeout (defaults to 10)

  • _no_expect (bool) – if True for,do not expect the usual command expectation (defaults to False)

  • _float_tol (tuple) – specify the float comparison tolerance, a 2-tuple containing a relative tolerance float value and an absolute tolerate float value (default to (1e-07, 1e-09)). See python 3 stdlib math.isclose documentation for more information

Supported by:

ANAFI Ai:

with an up to date firmware

Result: The drone sends state().

Expectations: state(uid=self.uid, state='idle', _policy='wait')

event message olympe.messages.mission.state(uid=None, state=None, unavailability_reason=None, list_flags=None, _policy='check_wait', _float_tol=(1e-07, 1e-09))#

mission.state

At connection and whenever there is a change in the mission state.

Parameters:
  • uid (string) – Unique id of the mission

  • state (olympe.enums.mission.state) – State of activation of the mission.

  • unavailability_reason (olympe.enums.mission.unavailability_reason) – Unavailability reason(s) to load the mission. Empty if mission is activate.

  • _policy (olympe.arsdkng.expectations.ExpectPolicy) – specify how to check the expectation. Possible values are ‘check’, ‘wait’ and ‘check_wait’ (defaults to ‘check_wait’)

  • _float_tol (tuple) – specify the float comparison tolerance, a 2-tuple containing a relative tolerance float value and an absolute tolerate float value (default to (1e-07, 1e-09)). See python 3 stdlib math.isclose documentation for more information

Supported by:

ANAFI Ai:

with an up to date firmware

event message olympe.messages.mission.suggested_activation(uid=None, list_flags=None, _policy='check_wait', _float_tol=(1e-07, 1e-09))#

mission.suggested_activation

Suggested activation of a mission.

Parameters:
  • uid (string) – Unique id of the mission

  • _policy (olympe.arsdkng.expectations.ExpectPolicy) – specify how to check the expectation. Possible values are ‘check’, ‘wait’ and ‘check_wait’ (defaults to ‘check_wait’)

  • _float_tol (tuple) – specify the float comparison tolerance, a 2-tuple containing a relative tolerance float value and an absolute tolerate float value (default to (1e-07, 1e-09)). See python 3 stdlib math.isclose documentation for more information

Supported by:

ANAFI Ai:

with an up to date firmware

Triggered When a mission is in idle mode, it can trigger this event

command message olympe.messages.mission.unload(uid, _timeout=10, _no_expect=False, _float_tol=(1e-07, 1e-09))#

mission.unload

Tells the drone to unload the mission.

Parameters:
  • uid (string) – Unique id of the mission

  • _timeout (int) – command message timeout (defaults to 10)

  • _no_expect (bool) – if True for,do not expect the usual command expectation (defaults to False)

  • _float_tol (tuple) – specify the float comparison tolerance, a 2-tuple containing a relative tolerance float value and an absolute tolerate float value (default to (1e-07, 1e-09)). See python 3 stdlib math.isclose documentation for more information

Supported by:

ANAFI Ai:

with an up to date firmware

Result: The drone sends state().

Expectations: state(uid=self.uid, state='unloaded', _policy='wait')

enum olympe.enums.mission.list_flags#

Arsdk built-in “list_flags” enum that is used to in “LIST_ITEM” event messages

First:

Arsdk built-in “list_flags” enum that is used to in “LIST_ITEM” event messages (0)

Last:

Arsdk built-in “list_flags” enum that is used to in “LIST_ITEM” event messages (1)

Empty:

Arsdk built-in “list_flags” enum that is used to in “LIST_ITEM” event messages (2)

Remove:

Arsdk built-in “list_flags” enum that is used to in “LIST_ITEM” event messages (3)

enum olympe.enums.mission.state#

State of mission.

unavailable:

Mission is not available. (0)

unloaded:

Mission is not available. (1)

idle:

Mission can be activated. (2)

active:

Mission is active. (3)

enum olympe.enums.mission.unavailability_reason#

Unavailability reasons.

none:

No reason. The mission is actually available. (0)

broken:

Broken. Version is not supported or mission is corrupted. The mission will never be able to load or start. (1)

load_failed:

The mission failed to load. (2)