6 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
Oleg Kalachev
af86699eb3 Add support form arm/disarm mavlink command 2025-07-30 14:36:57 +03:00
Oleg Kalachev
496888903f Make rc loss timeout longer 2025-07-29 22:04:19 +03:00
Oleg Kalachev
3cde9e69c4 Fixes 2025-07-29 22:04:04 +03:00
5 changed files with 18 additions and 6 deletions

View File

@@ -79,7 +79,7 @@ void interpretControls() {
if (mode == STAB) {
float yawTarget = attitudeTarget.getYaw();
if (invalid(yawTarget) || controlYaw != 0) yawTarget = attitude.getYaw(); // reset yaw target if NAN or yaw rate is set
if (invalid(yawTarget) || controlYaw != 0) yawTarget = attitude.getYaw(); // reset yaw target if NAN or pilot commands yaw rate
attitudeTarget = Quaternion::fromEuler(Vector(controlRoll * tiltMax, controlPitch * tiltMax, yawTarget));
ratesExtra = Vector(0, 0, -controlYaw * maxRate.z); // positive yaw stick means clockwise rotation in FLU
}
@@ -139,7 +139,7 @@ void controlTorque() {
if (!torqueTarget.valid()) return; // skip torque control
if (!armed || thrustTarget < 0.05) {
memset(motors, 0, sizeof(motors));
memset(motors, 0, sizeof(motors)); // stop motors if no thrust
return;
}

View File

@@ -3,7 +3,9 @@
// Fail-safe functions
#define RC_LOSS_TIMEOUT 0.2
#include "util.h"
#define RC_LOSS_TIMEOUT 0.5
#define DESCEND_TIME 3.0 // time to descend from full throttle to zero
extern double controlTime;
@@ -28,7 +30,7 @@ void autoFailsafe() {
static float roll, pitch, yaw, throttle;
if (roll != controlRoll || pitch != controlPitch || yaw != controlYaw || abs(throttle - controlThrottle) > 0.05) {
if (mode == AUTO && !isfinite(controlMode)) {
if (mode == AUTO && invalid(controlMode)) {
mode = STAB; // regain control to the pilot
}
}

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;
@@ -231,6 +231,12 @@ void handleMavlink(const void *_msg) {
mavlink_msg_command_ack_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &ack, m.command, MAV_RESULT_ACCEPTED, UINT8_MAX, 0, msg.sysid, msg.compid);
sendMessage(&ack);
}
if (m.command == MAV_CMD_COMPONENT_ARM_DISARM) {
armed = m.param1 == 1;
mavlink_msg_command_ack_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &ack, m.command, MAV_RESULT_ACCEPTED, UINT8_MAX, 0, msg.sysid, msg.compid);
sendMessage(&ack);
}
}
}

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"