3 Commits

Author SHA1 Message Date
Oleg Kalachev
d180a5d809 pyflix 0.6 2025-07-31 10:48:20 +03:00
Oleg Kalachev
8762ae0b38 Bring back handling old message for motor outputs in pyflix 2025-07-31 10:47:50 +03:00
Oleg Kalachev
2fcf35289e Set mavlink control scale to 1 by default 2025-07-30 20:05:03 +03:00
3 changed files with 6 additions and 2 deletions

View File

@@ -12,7 +12,7 @@
#define PERIOD_FAST 0.1
#define MAVLINK_CONTROL_YAW_DEAD_ZONE 0.1f
float mavlinkControlScale = 0.7;
float mavlinkControlScale = 1;
String mavlinkPrintBuffer;
extern double controlTime;

View File

@@ -173,6 +173,10 @@ class Flix:
self.motors = msg.controls[:4] # type: ignore
self._trigger('motors', self.motors)
# TODO: to be removed: the old way of passing motor outputs
if isinstance(msg, mavlink.MAVLink_actuator_output_status_message):
self.motors = msg.actuator[:4] # type: ignore
if isinstance(msg, mavlink.MAVLink_scaled_imu_message):
self.acc = self._mavlink_to_flu([msg.xacc / 1000, msg.yacc / 1000, msg.zacc / 1000])
self.gyro = self._mavlink_to_flu([msg.xgyro / 1000, msg.ygyro / 1000, msg.zgyro / 1000])

View File

@@ -1,6 +1,6 @@
[project]
name = "pyflix"
version = "0.5"
version = "0.6"
description = "Python API for Flix drone"
authors = [{ name="Oleg Kalachev", email="okalachev@gmail.com" }]
license = "MIT"