mirror of
https://github.com/okalachev/flix.git
synced 2026-01-10 04:57:17 +00:00
Minor updates to pyflix library, pyflix@0.10
Fixes to documentation. Improve logger format.
This commit is contained in:
@@ -1,8 +1,8 @@
|
||||
# Flix Python library
|
||||
|
||||
The Flix Python library allows you to remotely connect to a Flix quadcopter. It provides access to telemetry data, supports executing CLI commands, and controlling the drone's flight.
|
||||
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 local network as the simulator.
|
||||
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
|
||||
|
||||
@@ -30,7 +30,7 @@ flix = Flix() # create a Flix object and wait for connection
|
||||
|
||||
### Telemetry
|
||||
|
||||
Basic telemetry is available through object properties. The properties names generally match the corresponding variables in the firmware itself:
|
||||
Basic telemetry is available through object properties. The property names generally match the corresponding variables in the firmware itself:
|
||||
|
||||
```python
|
||||
print(flix.connected) # True if connected to the drone
|
||||
@@ -41,7 +41,7 @@ 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) # motors outputs (list)
|
||||
print(flix.motors) # motor outputs (list)
|
||||
print(flix.acc) # accelerometer output (list)
|
||||
print(flix.gyro) # gyroscope output (list)
|
||||
```
|
||||
@@ -100,17 +100,17 @@ Full list of events:
|
||||
|`attitude_euler`|Attitude update|Euler angles (*list*)|
|
||||
|`rates`|Angular rates update|Angular rates (*list*)|
|
||||
|`channels`|Raw RC channels update|Raw RC channels (*list*)|
|
||||
|`motors`|Motors outputs update|Motors outputs (*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 bellow)|Value|
|
||||
|`value.<name>`|Specific named value update (see below)|Value|
|
||||
|
||||
> [!NOTE]
|
||||
> Update events trigger on every new data from the drone, and do not mean the value has changed.
|
||||
> Update events trigger on every new piece of data from the drone, and do not mean the value has changed.
|
||||
|
||||
### Common methods
|
||||
|
||||
@@ -121,7 +121,7 @@ pitch_p = flix.get_param('PITCH_P') # get parameter value
|
||||
flix.set_param('PITCH_P', 5) # set parameter value
|
||||
```
|
||||
|
||||
Execute console commands using `cli` method. This method returns command response:
|
||||
Execute console commands using `cli` method. This method returns the command response:
|
||||
|
||||
```python
|
||||
imu = flix.cli('imu') # get detailed IMU data
|
||||
@@ -169,10 +169,10 @@ 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 motors outputs directly:
|
||||
You also can control raw motor outputs directly:
|
||||
|
||||
```python
|
||||
flix.set_motors([0.5, 0.5, 0.5, 0.5]) # set motors outputs in range [0, 1]
|
||||
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:
|
||||
@@ -186,7 +186,7 @@ The following methods are in development and are not functional yet:
|
||||
* `set_position` — set target position.
|
||||
* `set_velocity` — set target velocity.
|
||||
|
||||
To exit from *AUTO* mode move control sticks and the drone will switch to *STAB* mode.
|
||||
To exit *AUTO* mode move control sticks and the drone will switch to *STAB* mode.
|
||||
|
||||
## Usage alongside QGroundControl
|
||||
|
||||
|
||||
@@ -17,7 +17,7 @@ from pymavlink.dialects.v20 import common as mavlink
|
||||
logger = logging.getLogger('flix')
|
||||
if not logger.hasHandlers():
|
||||
handler = logging.StreamHandler()
|
||||
handler.setFormatter(logging.Formatter('%(name)s - %(levelname)s - %(message)s'))
|
||||
handler.setFormatter(logging.Formatter('%(name)s: %(message)s'))
|
||||
logger.addHandler(handler)
|
||||
logger.setLevel(logging.INFO)
|
||||
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
[project]
|
||||
name = "pyflix"
|
||||
version = "0.9"
|
||||
version = "0.10"
|
||||
description = "Python API for Flix drone"
|
||||
authors = [{ name="Oleg Kalachev", email="okalachev@gmail.com" }]
|
||||
license = "MIT"
|
||||
|
||||
Reference in New Issue
Block a user