Common.FlightPlan*#

event message olympe.messages.common.FlightPlanState.AvailabilityStateChanged(AvailabilityState=None, _policy='check_wait', _float_tol=(1e-07, 1e-09))#

common.FlightPlanState.AvailabilityStateChanged

FlightPlan availability. Availability is linked to GPS fix, magnetometer calibration, sensor states…

Parameters:
  • AvailabilityState (u8) – Running a flightPlan file is available (1 running a flightPlan file is available, otherwise 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 on change.

event message olympe.messages.common.FlightPlanState.ComponentStateListChanged(component=None, State=None, list_flags=None, _policy='check_wait', _float_tol=(1e-07, 1e-09))#

common.FlightPlanState.ComponentStateListChanged

FlightPlan components state list.

Parameters:
  • component (olympe.enums.common.FlightPlanState.ComponentStateListChanged_Component) –

  • State (u8) – State of the FlightPlan component (1 FlightPlan component OK, otherwise 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 the state of required components changes. GPS component is triggered when the availability of the GPS of the drone changes. Calibration component is triggered when the calibration state of the drone sensors changes Mavlink_File component is triggered when the command Start() is received. Takeoff component is triggered when the drone needs to take-off to continue the FlightPlan. WaypointsBeyondGeofence component is triggered when the command Start() is received.

event message olympe.messages.common.FlightPlanState.LockStateChanged(LockState=None, _policy='check_wait', _float_tol=(1e-07, 1e-09))#

common.FlightPlanState.LockStateChanged

FlightPlan lock state. Represents the fact that the controller is able or not to stop or pause a playing FlightPlan

Parameters:
  • LockState (u8) – 1 if FlightPlan is locked: can’t pause or stop FlightPlan. 0 if FlightPlan is unlocked: pause or stop available.

  • _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.FlightPlanState.LockStateChanged

Triggered when the lock changes.

enum olympe.enums.common.FlightPlanState.ComponentStateListChanged_Component#

Drone FlightPlan component id (unique)

GPS:

Drone GPS component. State is 0 when the drone needs a GPS fix. (0)

Calibration:

Drone Calibration component. State is 0 when the sensors of the drone needs to be calibrated. (1)

Mavlink_File:

Mavlink file component. State is 0 when the mavlink file is missing or contains error. (2)

TakeOff:

Drone Take off component. State is 0 when the drone cannot take-off. (3)

WaypointsBeyondGeofence:

Component for waypoints beyond the geofence. State is 0 when one or more waypoints are beyond the geofence. (4)

CameraAvailable:

Drone camera component. State is 0 when the drone needs to wait camera availability. (5)

Mavlink_State:

Mavlink state component. State is 0 when the mavlink did not start because of drone bad state. (6)

Mavlink_Media:

Mavlink Media component. State is 0 when the mavlink did not start because of a media action which cannot be performed. (7)

FirstWaypointTooFar:

Component for first waypoint too far away. State is 0 when the first waypoint in the flight plan is too far to be reached. (8)

event message olympe.messages.common.FlightPlanEvent.SpeedBridleEvent(_policy='check_wait', _float_tol=(1e-07, 1e-09))#

common.FlightPlanEvent.SpeedBridleEvent

FlightPlan speed clamping. Sent when a speed specified in the FlightPlan file is considered too high by the drone. This event is a notification, you can’t retrieve it in the cache of the device controller.

Parameters:
  • _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.FlightPlanEvent.SpeedBridleEvent

Triggered on an speed related clamping after a Start().

event message olympe.messages.common.FlightPlanEvent.StartingErrorEvent(_policy='check_wait', _float_tol=(1e-07, 1e-09))#

common.FlightPlanEvent.StartingErrorEvent

FlightPlan start error. This event is a notification, you can’t retrieve it in the cache of the device controller.

Parameters:
  • _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.FlightPlanEvent.StartingErrorEvent

Triggered on an error after a Start().