mirror of
https://github.com/okalachev/flix.git
synced 2026-01-11 21:46:55 +00:00
Compare commits
3 Commits
af86699eb3
...
robolager
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
d180a5d809 | ||
|
|
8762ae0b38 | ||
|
|
2fcf35289e |
@@ -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;
|
||||
|
||||
@@ -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])
|
||||
|
||||
@@ -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"
|
||||
|
||||
Reference in New Issue
Block a user