Ardrone3.SettingsState#

event message olympe.messages.ardrone3.SettingsState.CPUID(id=None, _policy='check_wait', _float_tol=(1e-07, 1e-09))#

ardrone3.SettingsState.CPUID

Product main cpu id

Parameters:
  • id (string) – Product main cpu id

  • _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 ardrone3.SettingsState.CPUID

event message olympe.messages.ardrone3.SettingsState.MotorErrorLastErrorChanged(motorError=None, _policy='check_wait', _float_tol=(1e-07, 1e-09))#

ardrone3.SettingsState.MotorErrorLastErrorChanged

Last motor error. This is a reminder of the last error. To know if a motor error is currently happening, see MotorErrorStateChanged().

Parameters:
  • motorError (olympe.enums.ardrone3.SettingsState.MotorErrorLastErrorChanged_MotorError) –

  • _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 at connection and when an error occurs.

event message olympe.messages.ardrone3.SettingsState.MotorErrorStateChanged(motorIds=None, motorError=None, _policy='check_wait', _float_tol=(1e-07, 1e-09))#

ardrone3.SettingsState.MotorErrorStateChanged

Motor error. This event is sent back to noError as soon as the motor error disappear. To get the last motor error, see MotorErrorLastErrorChanged()

Parameters:
  • motorIds (u8) – Bit field for concerned motor. If bit 0 = 1, motor 1 is affected by this error. Same with bit 1, 2 and 3. Motor 1: front left Motor 2: front right Motor 3: back right Motor 4: back left

  • motorError (olympe.enums.ardrone3.SettingsState.MotorErrorStateChanged_MotorError) –

  • _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 motor error occurs.

event message olympe.messages.ardrone3.SettingsState.MotorFlightsStatusChanged(nbFlights=None, lastFlightDuration=None, totalFlightDuration=None, _policy='check_wait', _float_tol=(1e-07, 1e-09))#

ardrone3.SettingsState.MotorFlightsStatusChanged

Motor flight status.

Parameters:
  • nbFlights (u16) – total number of flights

  • lastFlightDuration (u16) – Duration of the last flight (in seconds)

  • totalFlightDuration (u32) – Duration of all flights (in seconds)

  • _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 at connection.

event message olympe.messages.ardrone3.SettingsState.MotorSoftwareVersionChanged(version=None, _policy='check_wait', _float_tol=(1e-07, 1e-09))#

ardrone3.SettingsState.MotorSoftwareVersionChanged

Motor version.

Parameters:
  • version (string) – name of the version : dot separated fields (major version - minor version - firmware type - nb motors handled). Firmware types : Release, Debug, Alpha, Test-bench

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

Deprecated message

Warning

This message is deprecated and should no longer be used

event message olympe.messages.ardrone3.SettingsState.P7ID(serialID=None, _policy='check_wait', _float_tol=(1e-07, 1e-09))#

ardrone3.SettingsState.P7ID

P7ID.

Parameters:
  • serialID (string) – Product P7ID

  • _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 ardrone3.SettingsState.P7ID

Deprecated message

Warning

This message is deprecated and should no longer be used

event message olympe.messages.ardrone3.SettingsState.ProductGPSVersionChanged(software=None, hardware=None, _policy='check_wait', _float_tol=(1e-07, 1e-09))#

ardrone3.SettingsState.ProductGPSVersionChanged

GPS version.

Parameters:
  • software (string) – Product GPS software version

  • hardware (string) – Product GPS hardware version

  • _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 at connection.

event message olympe.messages.ardrone3.SettingsState.ProductMotorVersionListChanged(motor_number=None, type=None, software=None, hardware=None, list_flags=None, _policy='check_wait', _float_tol=(1e-07, 1e-09))#

ardrone3.SettingsState.ProductMotorVersionListChanged

Motor version.

Parameters:
  • motor_number (u8) – Product Motor number

  • type (string) – Product Motor type

  • software (string) – Product Motors software version

  • hardware (string) – Product Motors hardware version

  • _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 ardrone3.SettingsState.ProductMotorVersionListChanged

Deprecated message

Warning

This message is deprecated and should no longer be used

enum olympe.enums.ardrone3.SettingsState.MotorErrorLastErrorChanged_MotorError#

Enumeration of the motor error

noError:

No error detected (0)

errorEEPRom:

EEPROM access failure (1)

errorMotorStalled:

Motor stalled (2)

errorPropellerSecurity:

Propeller cutout security triggered (3)

errorCommLost:

Communication with motor failed by timeout (4)

errorRCEmergencyStop:

RC emergency stop (5)

errorRealTime:

Motor controler scheduler real-time out of bounds (6)

errorMotorSetting:

One or several incorrect values in motor settings (7)

errorBatteryVoltage:

Battery voltage out of bounds (8)

errorLipoCells:

Incorrect number of LIPO cells (9)

errorMOSFET:

Defectuous MOSFET or broken motor phases (10)

errorTemperature:

Too hot or too cold Cypress temperature (11)

errorBootloader:

Not use for BLDC but useful for HAL (12)

errorAssert:

Error Made by BLDC_ASSERT() (13)

enum olympe.enums.ardrone3.SettingsState.MotorErrorStateChanged_MotorError#

Enumeration of the motor error

noError:

No error detected (0)

errorEEPRom:

EEPROM access failure (1)

errorMotorStalled:

Motor stalled (2)

errorPropellerSecurity:

Propeller cutout security triggered (3)

errorCommLost:

Communication with motor failed by timeout (4)

errorRCEmergencyStop:

RC emergency stop (5)

errorRealTime:

Motor controler scheduler real-time out of bounds (6)

errorMotorSetting:

One or several incorrect values in motor settings (7)

errorTemperature:

Too hot or too cold Cypress temperature (8)

errorBatteryVoltage:

Battery voltage out of bounds (9)

errorLipoCells:

Incorrect number of LIPO cells (10)

errorMOSFET:

Defectuous MOSFET or broken motor phases (11)

errorBootloader:

Not use for BLDC but useful for HAL (12)

errorAssert:

Error Made by BLDC_ASSERT() (13)