Common.Settings*#
- command message olympe.messages.common.Settings.AllSettings(_timeout=10, _no_expect=False, _float_tol=(1e-07, 1e-09))#
common.Settings.AllSettings
Ask for all settings. Please note that you should not send this command if you are using the libARController API as this library is handling the connection process for you.
- 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 every drone product
Result: The product will trigger all settings events (such as
CameraSettingsChanged()
, or product specific settings as theMaxAltitudeChanged()
for the Bebop). Then, it will triggerAllSettingsChanged()
.Expectations:
AllSettingsChanged(_policy='wait')
- command message olympe.messages.common.Settings.AutoCountry(automatic, _timeout=10, _no_expect=False, _float_tol=(1e-07, 1e-09))#
common.Settings.AutoCountry
Enable auto-country. If auto-country is set, the drone will guess its Wifi country by itself by checking other Wifi country around it. Please note that you might be disconnected from the product after changing the country as it changes Wifi parameters.
- Parameters:
automatic (u8) – Boolean : 0 : Manual / 1 : Auto
_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
Unsupported message
Todo
Remove unsupported message common.Settings.AutoCountry
Result: The auto-country of the product is changed. Then, it will trigger
AutoCountryChanged()
andCountryChanged()
.Expectations:
AutoCountryChanged(automatic=self.automatic, _policy='wait')
&CountryChanged(_policy='wait')
- command message olympe.messages.common.Settings.Country(code, _timeout=10, _no_expect=False, _float_tol=(1e-07, 1e-09))#
common.Settings.Country
Set the country for Wifi products. This can modify Wifi band and/or channel. Please note that you might be disconnected from the product after changing the country as it changes Wifi parameters.
- Parameters:
code (string) – Country code with ISO 3166 format
_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
Unsupported message
Todo
Remove unsupported message common.Settings.Country
Result: The country is set. Then, it will trigger
CountryChanged()
.Expectations:
CountryChanged(code=self.code, _policy='wait')
- command message olympe.messages.common.Settings.ProductName(name, _timeout=10, _no_expect=False, _float_tol=(1e-07, 1e-09))#
common.Settings.ProductName
Set the product name. It also sets the name of the SSID for Wifi products and advertisement name for BLE products (changed after a reboot of the product).
- Parameters:
name (string) – Product name
_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 every drone product
Result: Name is changed. Then, it will trigger
ProductNameChanged()
.Expectations:
ProductNameChanged(name=self.name, _policy='wait')
- command message olympe.messages.common.Settings.Reset(_timeout=10, _no_expect=False, _float_tol=(1e-07, 1e-09))#
common.Settings.Reset
Reset all settings.
- 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 every drone product
Result: It will trigger
ResetChanged()
. Then, the product will trigger all settings events (such asCameraSettingsChanged()
, or product specific settings as theMaxAltitudeChanged()
for the Bebop) with factory values.Expectations:
ResetChanged(_policy='wait')
- event message olympe.messages.common.SettingsState.AllSettingsChanged(_policy='check_wait', _float_tol=(1e-07, 1e-09))#
common.SettingsState.AllSettingsChanged
All settings have been sent. Please note that you should not care about this event if you are using the libARController API as this library is handling the connection process for you.
- 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
Supported by every drone product
Triggered when all settings values have been sent.
- event message olympe.messages.common.SettingsState.AutoCountryChanged(automatic=None, _policy='check_wait', _float_tol=(1e-07, 1e-09))#
common.SettingsState.AutoCountryChanged
Auto-country changed.
- Parameters:
automatic (u8) – Boolean : 0 : Manual / 1 : Auto
_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 every drone product
Triggered by
AutoCountry()
.
- event message olympe.messages.common.SettingsState.BoardIdChanged(id=None, _policy='check_wait', _float_tol=(1e-07, 1e-09))#
common.SettingsState.BoardIdChanged
Board id.
- Parameters:
id (string) – Board 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
Supported by every drone product
Triggered during the connection process.
- event message olympe.messages.common.SettingsState.CountryChanged(code=None, _policy='check_wait', _float_tol=(1e-07, 1e-09))#
common.SettingsState.CountryChanged
Country changed.
- Parameters:
code (string) – Country code with ISO 3166 format, empty string means unknown country.
_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 every drone product
Triggered by
Country()
.
- event message olympe.messages.common.SettingsState.ProductNameChanged(name=None, _policy='check_wait', _float_tol=(1e-07, 1e-09))#
common.SettingsState.ProductNameChanged
Product name changed.
- Parameters:
name (string) – Product name
_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 every drone product
Triggered by
ProductName()
.
- event message olympe.messages.common.SettingsState.ProductSerialHighChanged(high=None, _policy='check_wait', _float_tol=(1e-07, 1e-09))#
common.SettingsState.ProductSerialHighChanged
Product serial (1st part).
- Parameters:
high (string) – Serial high number (hexadecimal value)
_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 every drone product
Triggered during the connection process.
- event message olympe.messages.common.SettingsState.ProductSerialLowChanged(low=None, _policy='check_wait', _float_tol=(1e-07, 1e-09))#
common.SettingsState.ProductSerialLowChanged
Product serial (2nd part).
- Parameters:
low (string) – Serial low number (hexadecimal value)
_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 every drone product
Triggered during the connection process.
- event message olympe.messages.common.SettingsState.ProductVersionChanged(software=None, hardware=None, _policy='check_wait', _float_tol=(1e-07, 1e-09))#
common.SettingsState.ProductVersionChanged
Product version.
- Parameters:
software (string) – Product software version
hardware (string) – Product 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 every drone product
Triggered during the connection process.
- event message olympe.messages.common.SettingsState.ResetChanged(_policy='check_wait', _float_tol=(1e-07, 1e-09))#
common.SettingsState.ResetChanged
All settings have been reset.
- 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
Supported by every drone product
Triggered by
Reset()
.