RTH feature#
- command message olympe.messages.rth.abort(_timeout=10, _no_expect=False, _float_tol=(1e-07, 1e-09))#
rth.abort
Abort a currently executing return to home.
- 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:
with an up to date firmware
- ANAFI Thermal:
with an up to date firmware
- ANAFI_UA:
with an up to date firmware
Result: The drone will abort its return home. Then, event
state()
is triggered.Expectations:
state(state='available', reason='stopped', _policy='wait')
- event message olympe.messages.rth.auto_trigger_mode(mode=None, _policy='check_wait', _float_tol=(1e-07, 1e-09))#
rth.auto_trigger_mode
RTH auto trigger mode
- Parameters:
mode (
olympe.enums.rth.auto_trigger_mode
) – RTH auto trigger mode._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
- ANAFI_UA:
with an up to date firmware
Triggered At connection; on changes.
- command message olympe.messages.rth.cancel_auto_trigger(_timeout=10, _no_expect=False, _float_tol=(1e-07, 1e-09))#
rth.cancel_auto_trigger
Cancel any current return home auto trigger. This command has no effect if there is no auto trigger currently planned (i.e. reason of
rth_auto_trigger()
is none).- 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:
with an up to date firmware
- ANAFI Thermal:
with an up to date firmware
Result: The drone will cancel its return home auto trigger. Then, event
rth_auto_trigger()
is triggered with reason set to none.Expectations:
rth_auto_trigger(reason='none', _policy='wait')
- event message olympe.messages.rth.custom_location(latitude=None, longitude=None, altitude=None, _policy='check_wait', _float_tol=(1e-07, 1e-09))#
rth.custom_location
Custom location
- Parameters:
latitude (double) – Latitude of the custom location
longitude (double) – Longitude of the custom location
altitude (float) – Altitude of the custom location above takeoff (ATO).
_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
- ANAFI_UA:
with an up to date firmware
Triggered by
set_custom_location()
- event message olympe.messages.rth.delay(delay=None, min=None, max=None, _policy='check_wait', _float_tol=(1e-07, 1e-09))#
rth.delay
Return home trigger delay. This delay represents the time after which the return home is automatically triggered after a disconnection.
- Parameters:
delay (u16) – Delay in second
min (u16) – Min delay in second
max (u16) – Max delay in second
_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
- ANAFI_UA:
with an up to date firmware
Triggered by
set_delay()
.
- event message olympe.messages.rth.ending_behavior(ending_behavior=None, _policy='check_wait', _float_tol=(1e-07, 1e-09))#
rth.ending_behavior
Ending behavior
- Parameters:
ending_behavior (
olympe.enums.rth.ending_behavior
) – Ending behavior action_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
- ANAFI_UA:
with an up to date firmware
Triggered when the ending behavior action changes and when setting a new ending behavior action has been refused by the drone.
- event message olympe.messages.rth.ending_hovering_altitude(current=None, min=None, max=None, _policy='check_wait', _float_tol=(1e-07, 1e-09))#
rth.ending_hovering_altitude
This altitude represents the altitude for the hovering at the end of rth. It is only used when ending_behavior is set to hovering.
- Parameters:
current (float) – Altitude used by the drone when hovering at the end of return home. This end altitude is AGL (above ground level).
min (float) – Range min of altitude
max (float) – Range max of altitude
_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
- ANAFI_UA:
with an up to date firmware
Triggered At connection; by
set_ending_hovering_altitude()
.
- event message olympe.messages.rth.followee_location(latitude=None, longitude=None, altitude=None, _policy='check_wait', _float_tol=(1e-07, 1e-09))#
rth.followee_location
Followee location
- Parameters:
latitude (double) – Latitude of the followee location
longitude (double) – Longitude of the followee location
altitude (float) – Altitude of the followee location above takeoff (ATO).
_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
- ANAFI_UA:
with an up to date firmware
Triggered regularly when drone is in FollowMe or LookAt with
gps()
sent.
- event message olympe.messages.rth.home_reachability(status=None, _policy='check_wait', _float_tol=(1e-07, 1e-09))#
rth.home_reachability
Home reachability status.
- Parameters:
status (
olympe.enums.rth.home_reachability
) – Status of the home reachability_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 home reachability status changes.
- event message olympe.messages.rth.home_type(type=None, _policy='check_wait', _float_tol=(1e-07, 1e-09))#
rth.home_type
Home type
- Parameters:
type (
olympe.enums.rth.home_type
) – Home 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
- ANAFI_UA:
with an up to date firmware
Triggered when the home type changes and when setting a new home type has been refused by the drone.
- event message olympe.messages.rth.home_type_capabilities(values=None, _policy='check_wait', _float_tol=(1e-07, 1e-09))#
rth.home_type_capabilities
Home type capabilities
- Parameters:
values (BitfieldOf(
olympe.enums.rth.home_type
, u32)) – Bitfield of supported home types._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
- ANAFI_UA:
with an up to date firmware
Triggered at connection.
- event message olympe.messages.rth.info(missing_inputs=None, _policy='check_wait', _float_tol=(1e-07, 1e-09))#
rth.info
Describes the missing requirements to start a return home.
- Parameters:
missing_inputs (BitfieldOf(
olympe.enums.rth.indicator
, u32)) – List of missing requirements to activate return home. If at least one input is missing, drone won’t be able to return home._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 During connection and when the list of missing requirements changes.
- event message olympe.messages.rth.min_altitude(current=None, min=None, max=None, _policy='check_wait', _float_tol=(1e-07, 1e-09))#
rth.min_altitude
This altitude represents the minimum altitude used by the drone during the return home.
- Parameters:
current (float) – Minimum altitude used by the drone during RTH. This value is above takeoff (ATO)
min (float) – Range min of altitude
max (float) – Range max of altitude
_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
- ANAFI_UA:
with an up to date firmware
Triggered by
set_min_altitude()
.
- event message olympe.messages.rth.preferred_home_type(type=None, _policy='check_wait', _float_tol=(1e-07, 1e-09))#
rth.preferred_home_type
Preferred home type. Please note that this is only a user preference. The actual type chosen is given by the event
home_type()
.- Parameters:
type (
olympe.enums.rth.home_type
) – Preferred Home 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
- ANAFI_UA:
with an up to date firmware
Triggered When the preferred return home type changes. This event is triggered by
set_preferred_home_type()
. Note: This is a user preference, the actual type chosen is given by the eventhome_type()
.
- command message olympe.messages.rth.return_to_home(_timeout=10, _no_expect=False, _float_tol=(1e-07, 1e-09))#
rth.return_to_home
Return home. Ask the drone to fly to its home position. Please note that the drone will wait to be hovering to start its return home. This means that it will wait to have a
PCMD()
set at 0.- 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:
with an up to date firmware
- ANAFI Thermal:
with an up to date firmware
- ANAFI_UA:
with an up to date firmware
Result: event
state()
is triggered. Then, the drone will fly back to its home position. You can get a state pending if the drone is not ready to start its return home process but will do it as soon as it is possible.Expectations: (
state(state='in_progress', reason='user_request', _policy='wait')
|state(state='pending', reason='user_request', _policy='wait')
)
- event message olympe.messages.rth.rth_auto_trigger(reason=None, delay=None, _policy='check_wait', _float_tol=(1e-07, 1e-09))#
rth.rth_auto_trigger
Return Home auto trigger information.
- Parameters:
reason (
olympe.enums.rth.auto_trigger_reason
) – Reason of the auto trigger.delay (u32) – Delay until the return home is automatically triggered by the drone, in seconds. If reason is none this information has no meaning.
_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 return home auto trigger information changes, then every seconds while reason is different from none.
- command message olympe.messages.rth.set_auto_trigger_mode(mode, _timeout=10, _no_expect=False, _float_tol=(1e-07, 1e-09))#
rth.set_auto_trigger_mode
Set mode for auto trigger return home
- Parameters:
mode (
olympe.enums.rth.auto_trigger_mode
) – Mode asked by user_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:
with an up to date firmware
- ANAFI Thermal:
with an up to date firmware
- ANAFI_UA:
with an up to date firmware
Result: Drone changes auto trigger mode. Event
auto_trigger_mode()
is triggered.Expectations:
auto_trigger_mode(mode=self.mode, _policy='wait')
- command message olympe.messages.rth.set_custom_location(latitude, longitude, altitude, _timeout=10, _no_expect=False, _float_tol=(1e-07, 1e-09))#
rth.set_custom_location
Set the custom location.
- Parameters:
latitude (double) – Latitude of the custom location
longitude (double) – Longitude of the custom location
altitude (float) – Altitude of the custom location above takeoff (ATO).
_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:
with an up to date firmware
- ANAFI Thermal:
with an up to date firmware
- ANAFI_UA:
with an up to date firmware
Result: If the drone knows its own location and if the custom location is not outside a circle centered on the drone with a radius equals to the max distance setting value, and if preferred home type (
set_preferred_home_type()
) is compatible,home_type()
is sent with type = custom, otherwise it is sent back with the former home type. Moreover,custom_location()
is sent by the drone.Expectations:
home_type(type='custom', _policy='wait')
&custom_location(latitude=self.latitude, longitude=self.longitude, altitude=self.altitude, _policy='wait')
- command message olympe.messages.rth.set_delay(delay, _timeout=10, _no_expect=False, _float_tol=(1e-07, 1e-09))#
rth.set_delay
Set the delay after which the drone will automatically try to return home after a disconnection.
- Parameters:
delay (u16) – Delay in second
_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:
with an up to date firmware
- ANAFI Thermal:
with an up to date firmware
- ANAFI_UA:
with an up to date firmware
Result: The delay of the return home is set. Then, event
delay()
is triggered.Expectations:
delay(delay=self.delay, _policy='wait')
- command message olympe.messages.rth.set_ending_behavior(ending_behavior, _timeout=10, _no_expect=False, _float_tol=(1e-07, 1e-09))#
rth.set_ending_behavior
Choose ending behavior action for RTH.
- Parameters:
ending_behavior (
olympe.enums.rth.ending_behavior
) – Ending behavior action_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:
with an up to date firmware
- ANAFI Thermal:
with an up to date firmware
- ANAFI_UA:
with an up to date firmware
Result: The ending behavior action is set to the new one. Event
ending_behavior()
is sent, otherwise it is sent back with the former ending behavior type.Expectations:
ending_behavior(ending_behavior=self.ending_behavior, _policy='wait')
- command message olympe.messages.rth.set_ending_hovering_altitude(altitude, _timeout=10, _no_expect=False, _float_tol=(1e-07, 1e-09))#
rth.set_ending_hovering_altitude
Set the return home ending hovering altitude. If the ending behavior action is set to hovering, Use this altitude.
- Parameters:
altitude (float) – Altitude used by the drone when hovering at the end of return home. This end altitude is AGL (above ground level).
_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:
with an up to date firmware
- ANAFI Thermal:
with an up to date firmware
- ANAFI_UA:
with an up to date firmware
Result: The ending altitude for the return home is set. Then, event
ending_hovering_altitude()
is triggered.Expectations:
ending_hovering_altitude(current=self.altitude, _policy='wait')
- command message olympe.messages.rth.set_min_altitude(altitude, _timeout=10, _no_expect=False, _float_tol=(1e-07, 1e-09))#
rth.set_min_altitude
Set the return home minimum altitude. If the drone is below this altitude when starting its return home, it will first reach the minimum altitude. If it is higher than this minimum altitude, it will operate its return home at its current altitude.
- Parameters:
altitude (float) – Return home min altitude above takeoff (ATO).
_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:
with an up to date firmware
- ANAFI Thermal:
with an up to date firmware
- ANAFI_UA:
with an up to date firmware
Result: The minimum altitude for the return home is set. Then, event
min_altitude()
is triggered.Expectations:
min_altitude(current=self.altitude, _policy='wait')
- command message olympe.messages.rth.set_preferred_home_type(type, _timeout=10, _no_expect=False, _float_tol=(1e-07, 1e-09))#
rth.set_preferred_home_type
Set the preferred home location type. The drone will always choose this home type when available.
- Parameters:
type (
olympe.enums.rth.home_type
) – Preferred home type._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:
with an up to date firmware
- ANAFI Thermal:
with an up to date firmware
- ANAFI_UA:
with an up to date firmware
Result: The drone returns
preferred_home_type()
. In addition, the drone returnshome_type()
with this value if the chosen home type is currently available.Expectations:
preferred_home_type(type=self.type, _policy='wait')
- event message olympe.messages.rth.state(state=None, reason=None, _policy='check_wait', _float_tol=(1e-07, 1e-09))#
rth.state
Return home state. Availability is related to gps fix, magnetometer calibration.
- Parameters:
state (
olympe.enums.rth.state
) – State of the return to homereason (
olympe.enums.rth.state_reason
) – Reason of the state change_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
- ANAFI_UA:
with an up to date firmware
Triggered on connection, by
return_to_home()
or byabort()
, or when the state of the return home changes.
- event message olympe.messages.rth.takeoff_location(latitude=None, longitude=None, altitude=None, fixed_before_takeoff=None, _policy='check_wait', _float_tol=(1e-07, 1e-09))#
rth.takeoff_location
Takeoff-type home location
- Parameters:
latitude (double) – Latitude of the takeoff location
longitude (double) – Longitude of the takeoff location
altitude (float) – Altitude of the takeoff home location above takeoff (ATO).
fixed_before_takeoff (u8) – 1 if the location was acquired before the takeoff. 0 if it was acquired during the flight (i.e. is it the first fix location).
_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
- ANAFI_UA:
with an up to date firmware
Triggered when takeoff home location is known by the drone. If gps is fixed at the time of the takeoff, then fixed_before_takeoff is true, otherwise is false.
- enum olympe.enums.rth.auto_trigger_mode#
RTH auto-trigger mode
Enum aliases:
- off:
Auto trigger is off. RTH auto trigger will never occur. (0)
- on:
Auto trigger is on. (1)
- enum olympe.enums.rth.auto_trigger_reason#
RTH auto-trigger reason
- none:
There is no return home auto trigger planned. (0)
- battery_critical_soon:
Battery will soon be critical. (1)
- enum olympe.enums.rth.ending_behavior#
RTH ending behavior action.
- landing:
The RTH end behavior is landing (0)
- hovering:
The RTH end behavior is hovering (1)
- enum olympe.enums.rth.home_reachability#
Home reachability
- unknown:
Home reachability is unknown (0)
- reachable:
Home is reachable (1)
- critical:
Home is still reachable but won’t be if rth is not triggered now. If rth is running, cancelling it will probably make the home not reachable. (2)
- not_reachable:
Home is not reachable (3)
- enum olympe.enums.rth.home_type#
Home type.
- none:
No home type. This might be because the drone does not have a gps fix (0)
- takeoff:
The drone will return to the last manual takeoff location (1)
- followee:
The drone will return to the followee position (2)
- custom:
The drone will return to a user-set custom location (3)
- pilot:
The drone will return to the pilot position (4)
- enum olympe.enums.rth.indicator#
Indicators needed to start an animation.
- drone_gps:
Drone gps is not fixed. (0)
- drone_magneto:
Drone magneto is not valid. (1)
- drone_geofence:
Drone is out of geofence. (2)
- drone_min_altitude:
Drone is under min altitude. (3)
- drone_max_altitude:
Drone is above max altitude. (4)
- drone_flying:
Drone is not flying. (5)
- target_position_accuracy:
Target position has a bad accuracy. (6)
- target_image_detection:
Target image detection is not working. (7)
- drone_target_distance_min:
Drone is too close to target. (8)
- drone_target_distance_max:
Drone is too far from target. (9)
- target_horiz_speed:
Target horizontal speed is too high. (10)
- target_vert_speed:
Target vertical speed is too high. (11)
- target_altitude_accuracy:
Target altitude has a bad accuracy. (12)
- drone_battery:
Drone battery is insufficient. (13)
- drone_state:
Drone is not in a valid state. (14)
- enum olympe.enums.rth.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.rth.state#
State of return to home
Enum aliases:
olympe.enums.ardrone3.NavigateHomeStateChanged_State
- available:
Return to home is available (0)
- in_progress:
Return to home is in progress (1)
- unavailable:
Return to home is not available (2)
- pending:
Return to home has been received, but its process is pending (3)
- enum olympe.enums.rth.state_reason#
Reason of the state
- user_request:
User requested a return to home (available->in_progress) (0)
- connection_lost:
Connection between controller and product lost (available->in_progress) (1)
- low_battery:
Low battery occurred (available->in_progress) (2)
- finished:
Return to home is finished (in_progress->available) (3)
- stopped:
Return to home has been stopped (in_progress->available) (4)
- disabled:
Return to home disabled by product (in_progress->unavailable or available->unavailable) (5)
- enabled:
Return to home enabled by product (unavailable->available) (6)
- flightplan:
Return to home during a flightplan (available->in_progress) (7)
- blocked:
Return to home could not find a path to home (in_progress->available) (8)
- icing:
Return to home triggered by propeller icing event (available->in_progress) (9)
- battery_lost_comm:
Return to home triggered by battery lost comm event (available->in_progress) (10)