Contents Menu Expand Light mode Dark mode Auto light/dark mode
7.7
Light Logo Dark Logo
7.7
  • Installation
    • Install a pre-built release via pip (x86_64 desktop only)
    • Building Olympe from source (for x86_64, armv7 or aarch64)
    • Python environment best practices on Debian-based distros
  • User guide
    • Introduction
    • Environment setup
    • Basic examples
      • Taking off - “Hello world” example
      • Getting the current value of a drone state or setting
      • Changing a drone setting - Understand the “expectation” mechanism
      • Moving around - Waiting for a ‘hovering’ flying state
      • Explore available ARSDK commands
    • Olympe eDSL
    • Advanced examples
      • Using Parrot AirSDK missions with Olympe
      • Using Olympe asynchronously
      • Using Olympe enums types
      • Adanced Olympe expectation usage
      • Capture the video streaming and its metadata
      • Post-processing a recorded video
      • Displaying the video streaming with an HUD
      • Connect to a physical drone
  • Olympe API Reference Documentation
  • Messages Reference Documentation
    • Animation feature
    • Alarms feature
    • Antenna feature
    • Antiflicker feature
    • Ardrone3 features
      • Ardrone3.Animations
      • Ardrone3.GPS*
      • Ardrone3.Piloting and SpeedSettings
      • Ardrone3.SettingsState
      • Ardrone3.Sound*
    • Auto Look At feature
    • Battery feature
    • Camera feature
    • Camera2 feature
    • Cellular feature
    • Common features
      • Common.Calibration*
      • Common.Common*
      • Common.Controller
      • Common.Factory
      • Common.FlightPlan*
      • Common.Mavlink*
      • Common.NetworkEvent
      • Common.RunState
      • Common.Settings*
      • Common.UpdateState
    • Connectivity feature
    • Controller Info feature
    • Controller Network feature
    • Controller Privacy feature
    • Debug feature
    • Developer feature
    • Device Manager feature
    • Drone Manager feature
    • DRI feature
    • Fcr feature
    • Flight Plan feature
    • FollowMe feature
    • Gauge Firmware Updater feature
    • Gimbal feature
    • Hand Land feature
    • LED feature
    • LEDS feature
    • Mapper feature
    • Mediastore feature
    • Microhard feature
    • Mission feature
    • Move feature
    • Network feature
    • NetDebugLog feature
    • Obstacle avoidance feature
    • Onboard Tracker feature
    • POI feature
    • PointNFly feature
    • Piloting Style feature
    • PreciseHome feature
    • Privacy feature
    • RTH feature
    • Security feature
    • Security Edition feature
    • Skyctrl features
      • Skyctrl.Calibration*
      • Skyctrl.Common*
      • Skyctrl.CommonEventState
      • Skyctrl.CoPiloting*
      • Skyctrl.Factory
      • Skyctrl.Settings*
      • Skyctrl.SkyControllerState
    • Stereo Vision Sensor feature
    • RC Transport feature
    • Thermal feature
    • UserStorage feature
    • UserStorage V2 feature
    • Wifi feature
Back to top

Common.Mavlink*#

command message olympe.messages.common.Mavlink.Pause(_timeout=20, _no_expect=False, _float_tol=(1e-07, 1e-09))#

common.Mavlink.Pause

Pause a FlightPlan that was playing. To unpause a FlightPlan, see Start()

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

  • _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:

with an up to date firmware

ANAFI Thermal:

with an up to date firmware

Result: The currently playing FlightPlan will be paused. Then, event MavlinkFilePlayingStateChanged() is triggered with param state set to the current state of the FlightPlan (should be paused if everything went well).

Expectations: MavlinkFilePlayingStateChanged(state='paused', _policy='wait')

command message olympe.messages.common.Mavlink.Start(filepath, type='flightPlan', _timeout=20, _no_expect=False, _float_tol=(1e-07, 1e-09))#

common.Mavlink.Start

Start a FlightPlan based on a mavlink file existing on the drone. Requirements are: * Product is calibrated * Product should be in outdoor mode * Product has fixed its GPS

Parameters:
  • filepath (string) – flight plan file path from the mavlink ftp root

  • type (olympe.enums.common.Mavlink.Start_Type) –

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

  • _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:

with an up to date firmware

ANAFI Thermal:

with an up to date firmware

Result: If the FlightPlan has been started, event MavlinkFilePlayingStateChanged() is triggered with param state set to playing. Otherwise, event MavlinkFilePlayingStateChanged() is triggered with param state set to stopped and event MavlinkPlayErrorStateChanged() is triggered with an explanation of the error.

Expectations: MavlinkFilePlayingStateChanged(state='playing', type=self.type, _policy='wait')

command message olympe.messages.common.Mavlink.Stop(_timeout=20, _no_expect=False, _float_tol=(1e-07, 1e-09))#

common.Mavlink.Stop

Stop a FlightPlan that was playing.

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

  • _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:

with an up to date firmware

ANAFI Thermal:

with an up to date firmware

Result: The currently playing FlightPlan will be stopped. Then, event MavlinkFilePlayingStateChanged() is triggered with param state set to the current state of the FlightPlan (should be stopped if everything went well).

Expectations: MavlinkFilePlayingStateChanged(state='stopped', _policy='wait')

enum olympe.enums.common.Mavlink.Start_Type#

type of the played mavlink file

Enum aliases:

  • olympe.enums.common.Start_Type

  • olympe.enums.common.MavlinkFilePlayingStateChanged_Type

  • olympe.enums.flight_plan.mavlink_type

flightPlan:

Mavlink file for FlightPlan (0)

mapMyHouse:

Mavlink file for MapMyHouse (1)

flightPlanV2:

Mavlink file for FlightPlan V2 (better follow the standard) (2)

event message olympe.messages.common.MavlinkState.MavlinkFilePlayingStateChanged(state=None, filepath=None, type=None, _policy='check_wait', _float_tol=(1e-07, 1e-09))#

common.MavlinkState.MavlinkFilePlayingStateChanged

Playing state of a FlightPlan.

Parameters:
  • state (olympe.enums.common.MavlinkState.MavlinkFilePlayingStateChanged_State) –

  • filepath (string) – flight plan file path from the mavlink ftp root

  • type (olympe.enums.common.MavlinkState.MavlinkFilePlayingStateChanged_Type) –

  • _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:

with an up to date firmware

ANAFI Thermal:

with an up to date firmware

Triggered by Start(), Pause() or Stop().

event message olympe.messages.common.MavlinkState.MavlinkPlayErrorStateChanged(error=None, _policy='check_wait', _float_tol=(1e-07, 1e-09))#

common.MavlinkState.MavlinkPlayErrorStateChanged

FlightPlan error.

Parameters:
  • error (olympe.enums.common.MavlinkState.MavlinkPlayErrorStateChanged_Error) –

  • _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

Unsupported message

Todo

Remove unsupported message common.MavlinkState.MavlinkPlayErrorStateChanged

Deprecated message

Warning

This message is deprecated and should no longer be used

Triggered by Start() if an error occurs.

event message olympe.messages.common.MavlinkState.MissionItemExecuted(idx=None, _policy='check_wait', _float_tol=(1e-07, 1e-09))#

common.MavlinkState.MissionItemExecuted

Mission item has been executed.

Parameters:
  • idx (u32) – Index of the mission item. This is the place of the mission item in the list of the items of the mission. Begins at 0.

  • _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:

with an up to date firmware

ANAFI Thermal:

with an up to date firmware

Triggered when a mission item has been executed during a flight plan.

enum olympe.enums.common.MavlinkState.MavlinkFilePlayingStateChanged_State#

State of the mavlink

playing:

Mavlink file is playing (0)

stopped:

Mavlink file is stopped (arg filepath and type are useless in this state) (1)

paused:

Mavlink file is paused (2)

loaded:

Mavlink file is loaded (it will be played at take-off) (3)

enum olympe.enums.common.MavlinkState.MavlinkFilePlayingStateChanged_Type#

type of the played mavlink file

Enum aliases:

  • olympe.enums.common.Start_Type

  • olympe.enums.common.MavlinkFilePlayingStateChanged_Type

  • olympe.enums.flight_plan.mavlink_type

flightPlan:

Mavlink file for FlightPlan (0)

mapMyHouse:

Mavlink file for MapMyHouse (1)

flightPlanV2:

Mavlink file for FlightPlan V2 (better follow the standard) (2)

enum olympe.enums.common.MavlinkState.MavlinkPlayErrorStateChanged_Error#

State of play error

none:

There is no error (0)

notInOutDoorMode:

The drone is not in outdoor mode (1)

gpsNotFixed:

The gps is not fixed (2)

notCalibrated:

The magnetometer of the drone is not calibrated (3)

Next
Common.NetworkEvent
Previous
Common.FlightPlan*
Copyright © 2018-2023, Parrot
Made with Sphinx and @pradyunsg's Furo
On this page
  • Common.Mavlink*
    • Pause
    • Start
    • Stop
    • Start_Type
    • MavlinkFilePlayingStateChanged
    • MavlinkPlayErrorStateChanged
    • MissionItemExecuted
    • MavlinkFilePlayingStateChanged_State
    • MavlinkFilePlayingStateChanged_Type
    • MavlinkPlayErrorStateChanged_Error