12 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
Oleg Kalachev
310b48f856 Fix 2025-07-29 21:32:50 +03:00
Oleg Kalachev
ce3e47d1ec Fix 2025-07-29 21:28:36 +03:00
Oleg Kalachev
cc362c1d4b Fixes 2025-07-29 18:22:56 +03:00
Oleg Kalachev
fc4feb8503 Fixed 2025-07-29 18:22:38 +03:00
Oleg Kalachev
3bbace6a1e Print armed state in rc command 2025-07-29 18:09:04 +03:00
Oleg Kalachev
a090e3543c Add WIFI_UDP_ALWAYS_BROADCAST define 2025-07-29 18:08:57 +03:00
8 changed files with 37 additions and 7 deletions

View File

@@ -40,6 +40,7 @@ const char* motd =
"cr - calibrate RC\n" "cr - calibrate RC\n"
"ca - calibrate accel\n" "ca - calibrate accel\n"
"mfr, mfl, mrr, mrl - test motor (remove props)\n" "mfr, mfl, mrr, mrl - test motor (remove props)\n"
"wifi - show Wi-Fi info\n"
"sys - show system info\n" "sys - show system info\n"
"reset - reset drone's state\n" "reset - reset drone's state\n"
"reboot - reboot the drone\n"; "reboot - reboot the drone\n";
@@ -142,6 +143,10 @@ void doCommand(String str, bool echo = false) {
testMotor(MOTOR_REAR_RIGHT); testMotor(MOTOR_REAR_RIGHT);
} else if (command == "mrl") { } else if (command == "mrl") {
testMotor(MOTOR_REAR_LEFT); testMotor(MOTOR_REAR_LEFT);
} else if (command == "wifi") {
#if WIFI_ENABLED
printWiFiInfo();
#endif
} else if (command == "sys") { } else if (command == "sys") {
#ifdef ESP32 #ifdef ESP32
print("Chip: %s\n", ESP.getChipModel()); print("Chip: %s\n", ESP.getChipModel());

View File

@@ -79,7 +79,7 @@ void interpretControls() {
if (mode == STAB) { if (mode == STAB) {
float yawTarget = attitudeTarget.getYaw(); 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)); attitudeTarget = Quaternion::fromEuler(Vector(controlRoll * tiltMax, controlPitch * tiltMax, yawTarget));
ratesExtra = Vector(0, 0, -controlYaw * maxRate.z); // positive yaw stick means clockwise rotation in FLU 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 (!torqueTarget.valid()) return; // skip torque control
if (!armed || thrustTarget < 0.05) { if (!armed || thrustTarget < 0.05) {
memset(motors, 0, sizeof(motors)); memset(motors, 0, sizeof(motors)); // stop motors if no thrust
return; return;
} }

View File

@@ -3,7 +3,9 @@
// Fail-safe functions // 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 #define DESCEND_TIME 3.0 // time to descend from full throttle to zero
extern double controlTime; extern double controlTime;
@@ -28,7 +30,7 @@ void autoFailsafe() {
static float roll, pitch, yaw, throttle; static float roll, pitch, yaw, throttle;
if (roll != controlRoll || pitch != controlPitch || yaw != controlYaw || abs(throttle - controlThrottle) > 0.05) { 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 mode = STAB; // regain control to the pilot
} }
} }

View File

@@ -12,7 +12,7 @@
#define PERIOD_FAST 0.1 #define PERIOD_FAST 0.1
#define MAVLINK_CONTROL_YAW_DEAD_ZONE 0.1f #define MAVLINK_CONTROL_YAW_DEAD_ZONE 0.1f
float mavlinkControlScale = 0.7; float mavlinkControlScale = 1;
String mavlinkPrintBuffer; String mavlinkPrintBuffer;
extern double controlTime; 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); 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); 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

@@ -13,6 +13,7 @@
#define WIFI_PASSWORD "flixwifi" #define WIFI_PASSWORD "flixwifi"
#define WIFI_UDP_PORT 14550 #define WIFI_UDP_PORT 14550
#define WIFI_UDP_REMOTE_PORT 14550 #define WIFI_UDP_REMOTE_PORT 14550
#define WIFI_UDP_ALWAYS_BROADCAST 1
WiFiUDP udp; WiFiUDP udp;
@@ -24,7 +25,9 @@ void setupWiFi() {
void sendWiFi(const uint8_t *buf, int len) { void sendWiFi(const uint8_t *buf, int len) {
if (WiFi.softAPIP() == IPAddress(0, 0, 0, 0) && WiFi.status() != WL_CONNECTED) return; if (WiFi.softAPIP() == IPAddress(0, 0, 0, 0) && WiFi.status() != WL_CONNECTED) return;
udp.beginPacket(WiFi.softAPBroadcastIP(), WIFI_UDP_REMOTE_PORT); IPAddress remote = WiFi.softAPBroadcastIP();
if (!WIFI_UDP_ALWAYS_BROADCAST && udp.remoteIP()) remote = udp.remoteIP();
udp.beginPacket(remote, WIFI_UDP_REMOTE_PORT);
udp.write(buf, len); udp.write(buf, len);
udp.endPacket(); udp.endPacket();
} }
@@ -34,4 +37,13 @@ int receiveWiFi(uint8_t *buf, int len) {
return udp.read(buf, len); return udp.read(buf, len);
} }
void printWiFiInfo() {
print("SSID: %s\n", WiFi.softAPSSID().c_str());
print("Clients: %d\n", WiFi.softAPgetStationNum());
print("Status: %d\n", WiFi.status());
print("IP: %s\n", WiFi.softAPIP().toString().c_str());
print("Remote IP: %s\n", udp.remoteIP().toString().c_str());
print("Broadcast IP: %s\n", WiFi.softAPBroadcastIP().toString().c_str());
}
#endif #endif

View File

@@ -72,4 +72,5 @@ void calibrateGyro() { print("Skip gyro calibrating\n"); };
void calibrateAccel() { print("Skip accel calibrating\n"); }; void calibrateAccel() { print("Skip accel calibrating\n"); };
void printIMUCalibration() { print("cal: N/A\n"); }; void printIMUCalibration() { print("cal: N/A\n"); };
void printIMUInfo() {}; void printIMUInfo() {};
void printWiFiInfo() {};
Vector accBias, gyroBias, accScale(1, 1, 1); Vector accBias, gyroBias, accScale(1, 1, 1);

View File

@@ -173,6 +173,10 @@ class Flix:
self.motors = msg.controls[:4] # type: ignore self.motors = msg.controls[:4] # type: ignore
self._trigger('motors', self.motors) 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): if isinstance(msg, mavlink.MAVLink_scaled_imu_message):
self.acc = self._mavlink_to_flu([msg.xacc / 1000, msg.yacc / 1000, msg.zacc / 1000]) 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]) self.gyro = self._mavlink_to_flu([msg.xgyro / 1000, msg.ygyro / 1000, msg.zgyro / 1000])

View File

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