Skip to main content

Python API for Flix drone

Project description

Flix Python library

The Flix Python library allows you to remotely connect to a Flix quadcopter. It provides access to telemetry data, supports executing console commands, and controlling the drone's flight.

To use the library, connect to the drone's Wi-Fi. To use it with the simulator, ensure the script runs on the same network as the simulator.

Installation

If you have cloned the repo, install the library from the repo:

cd /path/to/flix/repo
pip install -e tools

Alternatively, install from pip:

pip install pyflix

Usage

The API is accessed through the Flix class:

from flix import Flix
flix = Flix()  # create a Flix object and wait for connection

Telemetry

Basic telemetry is available through object properties. The property names generally match the corresponding variables in the firmware itself:

print(flix.connected)       # True if connected to the drone
print(flix.mode)            # current flight mode (str)
print(flix.armed)           # True if the drone is armed
print(flix.landed)          # True if the drone is landed
print(flix.voltage)         # battery voltage
print(flix.attitude)        # attitude quaternion [w, x, y, z]
print(flix.attitude_euler)  # attitude as Euler angles [roll, pitch, yaw]
print(flix.rates)           # angular rates [roll_rate, pitch_rate, yaw_rate]
print(flix.channels)        # raw RC channels (list)
print(flix.motors)          # motor outputs (list)
print(flix.acc)             # accelerometer output (list)
print(flix.gyro)            # gyroscope output (list)

The library uses the Front-Left-Up coordinate system — the same as the firmware:

All angles are in radians.

Events

The Flix object implements the Observable pattern, allowing to listen for events. You can subscribe to events using on method:

flix.on('connected', lambda: print('Connected to Flix'))
flix.on('disconnected', lambda: print('Disconnected from Flix'))
flix.on('print', lambda text: print(f'Flix says: {text}'))

Unsubscribe from events using off method:

flix.off('print')  # unsubscribe from print events
flix.off(callback)  # unsubscribe specific callback

You can also wait for specific events using wait method. This method returns the data associated with the event:

gyro = flix.wait('gyro')  # wait for gyroscope update
attitude = flix.wait('attitude', timeout=3)  # wait for attitude update, raise TimeoutError after 3 seconds

The second argument (value) specifies a condition for filtering events. It can be either an expected value or a callable:

flix.wait('armed', True)  # wait until armed
flix.wait('armed', False)  # wait until disarmed
flix.wait('mode', 'AUTO')  # wait until flight mode is switched to AUTO
flix.wait('motors', lambda motors: not any(motors))  # wait until all motors stop
flix.wait('attitude_euler', lambda att: att[0] > 0)  # wait until roll angle is positive

Full list of events:

Event Description Associated data
connected Connected to the drone
disconnected Connection is lost
armed Armed state update Armed state (bool)
mode Flight mode update Flight mode (str)
landed Landed state update Landed state (bool)
voltage Battery voltage update Voltage (float)
print The drone prints text to the console Text
attitude Attitude update Attitude quaternion (list)
attitude_euler Attitude update Euler angles (list)
rates Angular rates update Angular rates (list)
channels Raw RC channels update Raw RC channels (list)
motors Motor outputs update Motor outputs (list)
acc Accelerometer update Accelerometer output (list)
gyro Gyroscope update Gyroscope output (list)
mavlink Received MAVLink message Message object
mavlink.<message_name> Received specific MAVLink message Message object
mavlink.<message_id> Received specific MAVLink message Message object
value Named value update (see below) Name, value
value.<name> Specific named value update (see below) Value

[!NOTE] Update events trigger on every new piece of data from the drone, and do not mean the value has changed.

Basic methods

Get and set firmware parameters using get_param and set_param methods:

pitch_p = flix.get_param('CTL_P_P')  # get parameter value
flix.set_param('CTL_P_P', 5)         # set parameter value

Execute console commands using cli method. This method returns the command response:

imu = flix.cli('imu')    # get detailed IMU data
time = flix.cli('time')  # get detailed time data
flix.cli('reboot')       # reboot the drone

[!TIP] Use help command to get the list of available commands.

You can arm and disarm the drone using set_armed method (warning: the drone will fall if disarmed in the air):

flix.set_armed(True)   # arm the drone
flix.set_armed(False)  # disarm the drone

You can pass pilot's controls using set_controls method:

flix.set_controls(roll=0, pitch=0, yaw=0, throttle=0.6)

[!WARNING] This method is not intended for automatic flights, only for adding support for a custom pilot input device.

Automatic flight

To perform automatic flight, switch the mode to AUTO, either from the remote control, or from the code:

flix.set_mode('AUTO')

In this mode you can set flight control targets. Setting attitude target:

flix.set_attitude([0.1, 0.2, 0.3], 0.6)  # set target roll, pitch, yaw and thrust
flix.set_attitude([1, 0, 0, 0], 0.6)  # set target attitude quaternion and thrust

Setting angular rates target:

flix.set_rates([0.1, 0.2, 0.3], 0.6)  # set target roll rate, pitch rate, yaw rate and thrust

You also can control raw motor outputs directly:

flix.set_motors([0.5, 0.5, 0.5, 0.5])  # set motor outputs in range [0, 1]

In AUTO mode, the drone will arm automatically if the thrust is greater than zero, and disarm if thrust is zero. Therefore, to disarm the drone, set thrust to zero:

flix.set_attitude([0, 0, 0], 0)  # disarm the drone

The following methods are in development and are not functional yet:

  • set_position — set target position.
  • set_velocity — set target velocity.

To exit AUTO mode move control sticks and the drone will switch to STAB mode.

Usage alongside QGroundControl

You can use the Flix library alongside the QGroundControl app, using proxy mode. To do that:

  1. Run proxy for pyflix and QGroundControl in background:

    flix-proxy
    
  2. Go to QGroundControl settings ⇒ Comm Links.

  3. Add new link with the following settings:

    • Name: Proxy
    • Automatically Connect on Start: ✓
    • Type: UDP
    • Port: 14560
  4. Restart QGroundControl.

Now you can run pyflix scripts and QGroundControl simultaneously.

Tools

The following scripts demonstrate how to use the library:

  • cli.py — remote access to the drone's command line interface.
  • log.py — download flight logs from the drone.
  • example.py — a simple example, prints telemetry data and waits for events.

Advanced usage

MAVLink

You can access the most recently received messages using messages property:

print(flix.messages.get('HEARTBEAT'))  # print the latest HEARTBEAT message

You can wait for a specific message using wait method:

heartbeat = flix.wait('mavlink.HEARTBEAT')

You can send raw messages using mavlink property:

from pymavlink.dialects.v20 import common as mavlink

flix.mavlink.heartbeat_send(mavlink.MAV_TYPE_GCS, mavlink.MAV_AUTOPILOT_INVALID,
                            mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED, 0, 0)

Named values

You can pass arbitrary named values from the firmware to the Python script using NAMED_VALUE_FLOAT, NAMED_VALUE_INT, DEBUG, DEBUG_VECT, and DEBUG_FLOAT_ARRAY MAVLink messages.

All these named values will appear in the values dictionary:

print(flix.values['some_value'])
print(flix.values['some_vector'])

You can send values from the firmware like this (mavlink.ino):

// Send float named value
mavlink_msg_named_value_float_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, t, "loop_rate", loopRate);
sendMessage(&msg);

// Send vector named value
mavlink_msg_debug_vect_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, "gyro_bias", t, gyroBias.x, gyroBias.y, gyroBias.z);
sendMessage(&msg);

Logging

You can control Flix library verbosity using Python's logging module:

import logging

logger = logging.getLogger('flix')
logger.setLevel(logging.DEBUG)  # be more verbose
logger.setLevel(logging.WARNING)  # be less verbose

Project details


Download files

Download the file for your platform. If you're not sure which to choose, learn more about installing packages.

Source Distribution

pyflix-0.13.tar.gz (12.7 kB view details)

Uploaded Source

Built Distribution

If you're not sure about the file name format, learn more about wheel file names.

pyflix-0.13-py3-none-any.whl (13.8 kB view details)

Uploaded Python 3

File details

Details for the file pyflix-0.13.tar.gz.

File metadata

  • Download URL: pyflix-0.13.tar.gz
  • Upload date:
  • Size: 12.7 kB
  • Tags: Source
  • Uploaded using Trusted Publishing? No
  • Uploaded via: twine/6.1.0 CPython/3.13.11

File hashes

Hashes for pyflix-0.13.tar.gz
Algorithm Hash digest
SHA256 6a202da86ec20732c2819c24842ed578b2438335f118f2ad9297a611cf50f52f
MD5 d74cf60692263f790406c57944dd5b6d
BLAKE2b-256 18d5342b42cc9c2788aeeb199ee61183cf6ac6bbdc4cf1cd019fd5b4754b62e0

See more details on using hashes here.

File details

Details for the file pyflix-0.13-py3-none-any.whl.

File metadata

  • Download URL: pyflix-0.13-py3-none-any.whl
  • Upload date:
  • Size: 13.8 kB
  • Tags: Python 3
  • Uploaded using Trusted Publishing? No
  • Uploaded via: twine/6.1.0 CPython/3.13.11

File hashes

Hashes for pyflix-0.13-py3-none-any.whl
Algorithm Hash digest
SHA256 cdd7c023408e7ccba341b7fa3c37ba61a54eef984af312ddfc5f8d72f2c7aa71
MD5 22d4e3f1231baabf880e15362e5f43f8
BLAKE2b-256 a833c0e35e49be0b126e6f8be0770daaded2e15b25c3c99c71d9775c7fe78aaf

See more details on using hashes here.

Supported by

AWS Cloud computing and Security Sponsor Datadog Monitoring Depot Continuous Integration Fastly CDN Google Download Analytics Pingdom Monitoring Sentry Error logging StatusPage Status page