14 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
Oleg Kalachev
dfceb8a6b2 Implement auto mode for automatic flight
Use arm/disarm gestures
Add arm/disarm commands
Add ratesExtra variable for 
Rename interpretRC to interpretControls
Rename controlRate to controlRates
Remove USER mode
Add invalidate methods for vector and quaternion
Add valid/invalid method for vector and quaternion
Add valid/invalid function
Print armed in rc command
Pass auto mode to heartbeat
Use actuator_control_target for motors
2025-07-29 18:02:09 +03:00
Oleg Kalachev
2066d05a60 Implement set_mode, set_attitude and set_rates in pyflix 2025-07-28 22:36:41 +03:00
13 changed files with 247 additions and 101 deletions

View File

@@ -12,6 +12,7 @@ extern float loopRate, dt;
extern double t; extern double t;
extern uint16_t channels[16]; extern uint16_t channels[16];
extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlArmed, controlMode; extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlArmed, controlMode;
extern bool armed;
const char* motd = const char* motd =
"\nWelcome to\n" "\nWelcome to\n"
@@ -31,12 +32,15 @@ const char* motd =
"ps - show pitch/roll/yaw\n" "ps - show pitch/roll/yaw\n"
"psq - show attitude quaternion\n" "psq - show attitude quaternion\n"
"imu - show IMU data\n" "imu - show IMU data\n"
"arm - arm the drone (when no armed switch)\n"
"disarm - disarm the drone (when no armed switch)\n"
"rc - show RC data\n" "rc - show RC data\n"
"mot - show motor output\n" "mot - show motor output\n"
"log - dump in-RAM log\n" "log - dump in-RAM log\n"
"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";
@@ -109,6 +113,10 @@ void doCommand(String str, bool echo = false) {
printIMUCalibration(); printIMUCalibration();
print("rate: %.0f\n", loopRate); print("rate: %.0f\n", loopRate);
print("landed: %d\n", landed); print("landed: %d\n", landed);
} else if (command == "arm") {
armed = true;
} else if (command == "disarm") {
armed = false;
} else if (command == "rc") { } else if (command == "rc") {
print("channels: "); print("channels: ");
for (int i = 0; i < 16; i++) { for (int i = 0; i < 16; i++) {
@@ -117,6 +125,7 @@ void doCommand(String str, bool echo = false) {
print("\nroll: %g pitch: %g yaw: %g throttle: %g armed: %g mode: %g\n", print("\nroll: %g pitch: %g yaw: %g throttle: %g armed: %g mode: %g\n",
controlRoll, controlPitch, controlYaw, controlThrottle, controlArmed, controlMode); controlRoll, controlPitch, controlYaw, controlThrottle, controlArmed, controlMode);
print("mode: %s\n", getModeName()); print("mode: %s\n", getModeName());
print("armed: %d\n", armed);
} else if (command == "mot") { } else if (command == "mot") {
print("front-right %g front-left %g rear-right %g rear-left %g\n", print("front-right %g front-left %g rear-right %g rear-left %g\n",
motors[MOTOR_FRONT_RIGHT], motors[MOTOR_FRONT_LEFT], motors[MOTOR_REAR_RIGHT], motors[MOTOR_REAR_LEFT]); motors[MOTOR_FRONT_RIGHT], motors[MOTOR_FRONT_LEFT], motors[MOTOR_REAR_RIGHT], motors[MOTOR_REAR_LEFT]);
@@ -134,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

@@ -34,8 +34,7 @@
#define TILT_MAX radians(30) #define TILT_MAX radians(30)
#define RATES_D_LPF_ALPHA 0.2 // cutoff frequency ~ 40 Hz #define RATES_D_LPF_ALPHA 0.2 // cutoff frequency ~ 40 Hz
enum { MANUAL, ACRO, STAB, USER } mode = STAB; enum { MANUAL, ACRO, STAB, AUTO } mode = STAB;
enum { YAW, YAW_RATE } yawMode = YAW;
bool armed = false; bool armed = false;
PID rollRatePID(ROLLRATE_P, ROLLRATE_I, ROLLRATE_D, ROLLRATE_I_LIM, RATES_D_LPF_ALPHA); PID rollRatePID(ROLLRATE_P, ROLLRATE_I, ROLLRATE_D, ROLLRATE_I_LIM, RATES_D_LPF_ALPHA);
@@ -49,6 +48,7 @@ float tiltMax = TILT_MAX;
Quaternion attitudeTarget; Quaternion attitudeTarget;
Vector ratesTarget; Vector ratesTarget;
Vector ratesExtra; // feedforward rates
Vector torqueTarget; Vector torqueTarget;
float thrustTarget; float thrustTarget;
@@ -56,63 +56,50 @@ extern const int MOTOR_REAR_LEFT, MOTOR_REAR_RIGHT, MOTOR_FRONT_RIGHT, MOTOR_FRO
extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlArmed, controlMode; extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlArmed, controlMode;
void control() { void control() {
interpretRC(); interpretControls();
failsafe(); failsafe();
if (mode == STAB) { controlAttitude();
controlAttitude(); controlRates();
controlRate(); controlTorque();
controlTorque();
} else if (mode == ACRO) {
controlRate();
controlTorque();
} else if (mode == MANUAL) {
controlTorque();
}
} }
void interpretRC() { void interpretControls() {
armed = controlThrottle >= 0.05 && controlArmed >= 0.5;
// NOTE: put ACRO or MANUAL modes there if you want to use them // NOTE: put ACRO or MANUAL modes there if you want to use them
if (controlMode < 0.25) { if (controlMode < 0.25) mode = STAB;
mode = STAB; if (controlMode < 0.75) mode = STAB;
} else if (controlMode < 0.75) { if (controlMode > 0.75) mode = AUTO;
mode = STAB; if (controlArmed < 0.5) armed = false;
} else {
mode = STAB; if (mode == AUTO) return; // pilot is not effective in AUTO mode
}
if (landed && controlThrottle == 0 && controlYaw > 0.95) armed = true; // arm gesture
if (landed && controlThrottle == 0 && controlYaw < -0.95) armed = false; // disarm gesture
thrustTarget = controlThrottle; thrustTarget = controlThrottle;
if (mode == ACRO) { if (mode == STAB) {
yawMode = YAW_RATE; float yawTarget = attitudeTarget.getYaw();
ratesTarget.x = controlRoll * maxRate.x; if (invalid(yawTarget) || controlYaw != 0) yawTarget = attitude.getYaw(); // reset yaw target if NAN or pilot commands yaw rate
ratesTarget.y = controlPitch* maxRate.y; attitudeTarget = Quaternion::fromEuler(Vector(controlRoll * tiltMax, controlPitch * tiltMax, yawTarget));
ratesTarget.z = -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
} else if (mode == STAB) {
yawMode = controlYaw == 0 ? YAW : YAW_RATE;
attitudeTarget = Quaternion::fromEuler(Vector(
controlRoll * tiltMax,
controlPitch * tiltMax,
attitudeTarget.getYaw()));
ratesTarget.z = -controlYaw * maxRate.z; // positive yaw stick means clockwise rotation in FLU
} else if (mode == MANUAL) {
// passthrough mode
yawMode = YAW_RATE;
torqueTarget = Vector(controlRoll, controlPitch, -controlYaw) * 0.01;
} }
if (yawMode == YAW_RATE || !motorsActive()) { if (mode == ACRO) {
// update yaw target as we don't have control over the yaw attitudeTarget.invalidate();
attitudeTarget.setYaw(attitude.getYaw()); ratesTarget.x = controlRoll * maxRate.x;
ratesTarget.y = controlPitch * maxRate.y;
ratesTarget.z = -controlYaw * maxRate.z; // positive yaw stick means clockwise rotation in FLU
}
if (mode == MANUAL) { // passthrough mode
attitudeTarget.invalidate();
ratesTarget.invalidate();
torqueTarget = Vector(controlRoll, controlPitch, -controlYaw) * 0.01;
} }
} }
void controlAttitude() { void controlAttitude() {
if (!armed) { if (!armed || attitudeTarget.invalid()) { // skip attitude control
rollPID.reset(); rollPID.reset();
pitchPID.reset(); pitchPID.reset();
yawPID.reset(); yawPID.reset();
@@ -125,17 +112,15 @@ void controlAttitude() {
Vector error = Vector::rotationVectorBetween(upTarget, upActual); Vector error = Vector::rotationVectorBetween(upTarget, upActual);
ratesTarget.x = rollPID.update(error.x, dt); ratesTarget.x = rollPID.update(error.x, dt) + ratesExtra.x;
ratesTarget.y = pitchPID.update(error.y, dt); ratesTarget.y = pitchPID.update(error.y, dt) + ratesExtra.y;
if (yawMode == YAW) { float yawError = wrapAngle(attitudeTarget.getYaw() - attitude.getYaw());
float yawError = wrapAngle(attitudeTarget.getYaw() - attitude.getYaw()); ratesTarget.z = yawPID.update(yawError, dt) + ratesExtra.z;
ratesTarget.z = yawPID.update(yawError, dt);
}
} }
void controlRate() { void controlRates() {
if (!armed) { if (!armed || ratesTarget.invalid()) { // skip rates control
rollRatePID.reset(); rollRatePID.reset();
pitchRatePID.reset(); pitchRatePID.reset();
yawRatePID.reset(); yawRatePID.reset();
@@ -151,8 +136,10 @@ void controlRate() {
} }
void controlTorque() { void controlTorque() {
if (!armed) { if (!torqueTarget.valid()) return; // skip torque control
memset(motors, 0, sizeof(motors));
if (!armed || thrustTarget < 0.05) {
memset(motors, 0, sizeof(motors)); // stop motors if no thrust
return; return;
} }
@@ -172,7 +159,7 @@ const char* getModeName() {
case MANUAL: return "MANUAL"; case MANUAL: return "MANUAL";
case ACRO: return "ACRO"; case ACRO: return "ACRO";
case STAB: return "STAB"; case STAB: return "STAB";
case USER: return "USER"; case AUTO: return "AUTO";
default: return "UNKNOWN"; default: return "UNKNOWN";
} }
} }

View File

@@ -3,39 +3,48 @@
// 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;
extern float controlRoll, controlPitch, controlThrottle, controlYaw; extern float controlRoll, controlPitch, controlThrottle, controlYaw;
void failsafe() { void failsafe() {
armingFailsafe();
rcLossFailsafe(); rcLossFailsafe();
} autoFailsafe();
// Prevent arming without zero throttle input
void armingFailsafe() {
static double zeroThrottleTime;
static double armingTime;
if (!armed) armingTime = t; // stores the last time when the drone was disarmed, therefore contains arming time
if (controlTime > 0 && controlThrottle < 0.05) zeroThrottleTime = controlTime;
if (armingTime - zeroThrottleTime > 0.1) armed = false; // prevent arming if there was no zero throttle for 0.1 sec
} }
// RC loss failsafe // RC loss failsafe
void rcLossFailsafe() { void rcLossFailsafe() {
if (mode == AUTO) return;
if (!armed) return;
if (t - controlTime > RC_LOSS_TIMEOUT) { if (t - controlTime > RC_LOSS_TIMEOUT) {
descend(); descend();
} }
} }
// Allow pilot to interrupt automatic flight
void autoFailsafe() {
static float roll, pitch, yaw, throttle;
if (roll != controlRoll || pitch != controlPitch || yaw != controlYaw || abs(throttle - controlThrottle) > 0.05) {
if (mode == AUTO && invalid(controlMode)) {
mode = STAB; // regain control to the pilot
}
}
roll = controlRoll;
pitch = controlPitch;
yaw = controlYaw;
throttle = controlThrottle;
}
// Smooth descend on RC lost // Smooth descend on RC lost
void descend() { void descend() {
mode = STAB; mode = AUTO;
controlRoll = 0; thrustTarget -= dt / DESCEND_TIME;
controlPitch = 0; if (thrustTarget < 0) thrustTarget = 0;
controlYaw = 0; if (thrustTarget == 0) armed = false;
controlThrottle -= dt / DESCEND_TIME;
if (controlThrottle < 0) controlThrottle = 0;
} }

View File

@@ -12,7 +12,8 @@
double t = NAN; // current step time, s double t = NAN; // current step time, s
float dt; // time delta from previous step, s float dt; // time delta from previous step, s
float controlRoll, controlPitch, controlYaw, controlThrottle, controlArmed, controlMode; // pilot's inputs, range [-1, 1] float controlRoll, controlPitch, controlYaw, controlThrottle; // pilot's inputs, range [-1, 1]
float controlArmed = NAN, controlMode = NAN;
Vector gyro; // gyroscope data Vector gyro; // gyroscope data
Vector acc; // accelerometer data, m/s/s Vector acc; // accelerometer data, m/s/s
Vector rates; // filtered angular rates, rad/s Vector rates; // filtered angular rates, rad/s

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;
@@ -36,7 +36,9 @@ void sendMavlink() {
lastSlow = t; lastSlow = t;
mavlink_msg_heartbeat_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, MAV_TYPE_QUADROTOR, MAV_AUTOPILOT_GENERIC, mavlink_msg_heartbeat_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, MAV_TYPE_QUADROTOR, MAV_AUTOPILOT_GENERIC,
MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | (armed * MAV_MODE_FLAG_SAFETY_ARMED) | ((mode == STAB) * MAV_MODE_FLAG_STABILIZE_ENABLED), (armed * MAV_MODE_FLAG_SAFETY_ARMED) |
(mode == STAB) * MAV_MODE_FLAG_STABILIZE_ENABLED |
((mode == AUTO) ? MAV_MODE_FLAG_AUTO_ENABLED : MAV_MODE_FLAG_MANUAL_INPUT_ENABLED),
mode, MAV_STATE_STANDBY); mode, MAV_STATE_STANDBY);
sendMessage(&msg); sendMessage(&msg);
@@ -57,9 +59,9 @@ void sendMavlink() {
channels[0], channels[1], channels[2], channels[3], channels[4], channels[5], channels[6], channels[7], UINT8_MAX); channels[0], channels[1], channels[2], channels[3], channels[4], channels[5], channels[6], channels[7], UINT8_MAX);
if (channels[0] != 0) sendMessage(&msg); // 0 means no RC input if (channels[0] != 0) sendMessage(&msg); // 0 means no RC input
float actuator[32]; float controls[8];
memcpy(actuator, motors, sizeof(motors)); memcpy(controls, motors, sizeof(motors));
mavlink_msg_actuator_output_status_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, time, 4, actuator); mavlink_msg_actuator_control_target_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, time, 0, controls);
sendMessage(&msg); sendMessage(&msg);
mavlink_msg_scaled_imu_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, time, mavlink_msg_scaled_imu_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, time,
@@ -102,8 +104,8 @@ void handleMavlink(const void *_msg) {
controlPitch = m.x / 1000.0f * mavlinkControlScale; controlPitch = m.x / 1000.0f * mavlinkControlScale;
controlRoll = m.y / 1000.0f * mavlinkControlScale; controlRoll = m.y / 1000.0f * mavlinkControlScale;
controlYaw = m.r / 1000.0f * mavlinkControlScale; controlYaw = m.r / 1000.0f * mavlinkControlScale;
controlMode = 1; // STAB mode controlMode = NAN; // keep mode
controlArmed = 1; // armed controlArmed = NAN;
controlTime = t; controlTime = t;
if (abs(controlYaw) < MAVLINK_CONTROL_YAW_DEAD_ZONE) controlYaw = 0; if (abs(controlYaw) < MAVLINK_CONTROL_YAW_DEAD_ZONE) controlYaw = 0;
@@ -174,6 +176,39 @@ void handleMavlink(const void *_msg) {
doCommand(data, true); doCommand(data, true);
} }
if (msg.msgid == MAVLINK_MSG_ID_SET_ATTITUDE_TARGET) {
if (mode != AUTO) return;
mavlink_set_attitude_target_t m;
mavlink_msg_set_attitude_target_decode(&msg, &m);
if (m.target_system && m.target_system != SYSTEM_ID) return;
// copy attitude, rates and thrust targets
ratesTarget.x = m.body_roll_rate;
ratesTarget.y = -m.body_pitch_rate; // convert to flu
ratesTarget.z = -m.body_yaw_rate;
attitudeTarget.w = m.q[0];
attitudeTarget.x = m.q[1];
attitudeTarget.y = -m.q[2];
attitudeTarget.z = -m.q[3];
thrustTarget = m.thrust;
ratesExtra = Vector(0, 0, 0);
if (m.type_mask & ATTITUDE_TARGET_TYPEMASK_ATTITUDE_IGNORE) attitudeTarget.invalidate();
armed = m.thrust > 0;
}
if (msg.msgid == MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET) {
if (mode != AUTO) return;
mavlink_set_actuator_control_target_t m;
mavlink_msg_set_actuator_control_target_decode(&msg, &m);
if (m.target_system && m.target_system != SYSTEM_ID) return;
memcpy(motors, m.controls, sizeof(motors)); // copy motor thrusts
}
// Handle commands // Handle commands
if (msg.msgid == MAVLINK_MSG_ID_COMMAND_LONG) { if (msg.msgid == MAVLINK_MSG_ID_COMMAND_LONG) {
mavlink_command_long_t m; mavlink_command_long_t m;
@@ -188,8 +223,18 @@ void handleMavlink(const void *_msg) {
mavlink_msg_autopilot_version_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &response, mavlink_msg_autopilot_version_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &response,
MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT | MAV_PROTOCOL_CAPABILITY_MAVLINK2, 1, 0, 1, 1, 0, 0, 0, 0, 0, 0, 0); MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT | MAV_PROTOCOL_CAPABILITY_MAVLINK2, 1, 0, 1, 1, 0, 0, 0, 0, 0, 0, 0);
sendMessage(&response); sendMessage(&response);
} else { }
mavlink_msg_command_ack_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &ack, m.command, MAV_RESULT_UNSUPPORTED, UINT8_MAX, 0, msg.sysid, msg.compid);
if (m.command == MAV_CMD_DO_SET_MODE) {
if (!(m.param2 >= 0 && m.param2 <= AUTO)) return;
mode = static_cast<decltype(mode)>(m.param2);
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); sendMessage(&ack);
} }
} }

View File

@@ -64,6 +64,21 @@ public:
return isfinite(w) && isfinite(x) && isfinite(y) && isfinite(z); return isfinite(w) && isfinite(x) && isfinite(y) && isfinite(z);
} }
bool valid() const {
return finite();
}
bool invalid() const {
return !valid();
}
void invalidate() {
w = NAN;
x = NAN;
y = NAN;
z = NAN;
}
float norm() const { float norm() const {
return sqrt(w * w + x * x + y * y + z * z); return sqrt(w * w + x * x + y * y + z * z);
} }

View File

@@ -42,7 +42,7 @@ void normalizeRC() {
controlPitch = pitchChannel >= 0 ? controls[(int)pitchChannel] : NAN; controlPitch = pitchChannel >= 0 ? controls[(int)pitchChannel] : NAN;
controlYaw = yawChannel >= 0 ? controls[(int)yawChannel] : NAN; controlYaw = yawChannel >= 0 ? controls[(int)yawChannel] : NAN;
controlThrottle = throttleChannel >= 0 ? controls[(int)throttleChannel] : NAN; controlThrottle = throttleChannel >= 0 ? controls[(int)throttleChannel] : NAN;
controlArmed = armedChannel >= 0 ? controls[(int)armedChannel] : 1; // assume armed by default controlArmed = armedChannel >= 0 ? controls[(int)armedChannel] : NAN;
controlMode = modeChannel >= 0 ? controls[(int)modeChannel] : NAN; controlMode = modeChannel >= 0 ? controls[(int)modeChannel] : NAN;
} }

View File

@@ -19,6 +19,14 @@ float mapff(float x, float in_min, float in_max, float out_min, float out_max) {
return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min; return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
} }
bool invalid(float x) {
return !isfinite(x);
}
bool valid(float x) {
return isfinite(x);
}
// Wrap angle to [-PI, PI) // Wrap angle to [-PI, PI)
float wrapAngle(float angle) { float wrapAngle(float angle) {
angle = fmodf(angle, 2 * PI); angle = fmodf(angle, 2 * PI);

View File

@@ -21,6 +21,20 @@ public:
return isfinite(x) && isfinite(y) && isfinite(z); return isfinite(x) && isfinite(y) && isfinite(z);
} }
bool valid() const {
return finite();
}
bool invalid() const {
return !valid();
}
void invalidate() {
x = NAN;
y = NAN;
z = NAN;
}
float norm() const { float norm() const {
return sqrt(x * x + y * y + z * z); return sqrt(x * x + y * y + z * z);
} }

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

@@ -15,7 +15,8 @@
double t = NAN; double t = NAN;
float dt; float dt;
float motors[4]; float motors[4];
float controlRoll, controlPitch, controlYaw, controlThrottle, controlArmed, controlMode; float controlRoll, controlPitch, controlYaw, controlThrottle = NAN;
float controlArmed = NAN, controlMode = NAN;
Vector acc; Vector acc;
Vector gyro; Vector gyro;
Vector rates; Vector rates;
@@ -28,9 +29,9 @@ void computeLoopRate();
void applyGyro(); void applyGyro();
void applyAcc(); void applyAcc();
void control(); void control();
void interpretRC(); void interpretControls();
void controlAttitude(); void controlAttitude();
void controlRate(); void controlRates();
void controlTorque(); void controlTorque();
const char* getModeName(); const char* getModeName();
void sendMotors(); void sendMotors();
@@ -54,8 +55,8 @@ void mavlinkPrint(const char* str);
void sendMavlinkPrint(); void sendMavlinkPrint();
inline Quaternion fluToFrd(const Quaternion &q); inline Quaternion fluToFrd(const Quaternion &q);
void failsafe(); void failsafe();
void armingFailsafe();
void rcLossFailsafe(); void rcLossFailsafe();
void autoFailsafe();
void descend(); void descend();
int parametersCount(); int parametersCount();
const char *getParameterName(int index); const char *getParameterName(int index);
@@ -71,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

@@ -6,7 +6,7 @@
import os import os
import time import time
from queue import Queue, Empty from queue import Queue, Empty
from typing import Literal, Optional, Callable, List, Dict, Any, Union from typing import Literal, Optional, Callable, List, Dict, Any, Union, Sequence
import logging import logging
import errno import errno
from threading import Thread, Timer from threading import Thread, Timer
@@ -40,6 +40,7 @@ class Flix:
_connection_timeout = 3 _connection_timeout = 3
_print_buffer: str = '' _print_buffer: str = ''
_modes = ['MANUAL', 'ACRO', 'STAB', 'AUTO']
def __init__(self, system_id: int=1, wait_connection: bool=True): def __init__(self, system_id: int=1, wait_connection: bool=True):
if not (0 <= system_id < 256): if not (0 <= system_id < 256):
@@ -55,7 +56,7 @@ class Flix:
if e.errno != errno.EADDRINUSE: if e.errno != errno.EADDRINUSE:
raise raise
# Port busy - using proxy # Port busy - using proxy
logger.debug('Listening on port 14560 (proxy)') logger.debug('Listening on port 14555 (proxy)')
self.connection: mavutil.mavfile = mavutil.mavlink_connection('udpin:0.0.0.0:14555', source_system=254) # type: ignore self.connection: mavutil.mavfile = mavutil.mavlink_connection('udpin:0.0.0.0:14555', source_system=254) # type: ignore
self.connection.target_system = system_id self.connection.target_system = system_id
self.mavlink: mavlink.MAVLink = self.connection.mav self.mavlink: mavlink.MAVLink = self.connection.mav
@@ -147,7 +148,7 @@ class Flix:
def _handle_mavlink_message(self, msg: mavlink.MAVLink_message): def _handle_mavlink_message(self, msg: mavlink.MAVLink_message):
if isinstance(msg, mavlink.MAVLink_heartbeat_message): if isinstance(msg, mavlink.MAVLink_heartbeat_message):
self.mode = ['MANUAL', 'ACRO', 'STAB', 'USER'][msg.custom_mode] self.mode = self._modes[msg.custom_mode]
self.armed = msg.base_mode & mavlink.MAV_MODE_FLAG_SAFETY_ARMED != 0 self.armed = msg.base_mode & mavlink.MAV_MODE_FLAG_SAFETY_ARMED != 0
self._trigger('mode', self.mode) self._trigger('mode', self.mode)
self._trigger('armed', self.armed) self._trigger('armed', self.armed)
@@ -168,9 +169,13 @@ class Flix:
msg.chan5_raw, msg.chan6_raw, msg.chan7_raw, msg.chan8_raw] msg.chan5_raw, msg.chan6_raw, msg.chan7_raw, msg.chan8_raw]
self._trigger('channels', self.channels) self._trigger('channels', self.channels)
if isinstance(msg, mavlink.MAVLink_actuator_control_target_message):
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): if isinstance(msg, mavlink.MAVLink_actuator_output_status_message):
self.motors = msg.actuator[:4] # type: ignore self.motors = msg.actuator[:4] # type: ignore
self._trigger('motors', self.motors)
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])
@@ -231,6 +236,19 @@ class Flix:
def _flu_to_mavlink(v: List[float]) -> List[float]: def _flu_to_mavlink(v: List[float]) -> List[float]:
return Flix._mavlink_to_flu(v) return Flix._mavlink_to_flu(v)
def _command_send(self, command: int, params: Sequence[float]):
if len(params) != 7:
raise ValueError('Command must have 7 parameters')
for attempt in range(3):
try:
logger.debug(f'Send command {command} with params {params} (attempt #{attempt + 1})')
self.mavlink.command_long_send(self.system_id, 0, command, 0, *params) # type: ignore
self.wait('mavlink.COMMAND_ACK', value=lambda msg: msg.command == command and msg.result == mavlink.MAV_RESULT_ACCEPTED, timeout=0.1)
return
except TimeoutError:
continue
raise RuntimeError(f'Failed to send command {command} after 3 attempts')
def _connected(self): def _connected(self):
# Reset disconnection timer # Reset disconnection timer
self._disconnected_timer.cancel() self._disconnected_timer.cancel()
@@ -275,6 +293,11 @@ class Flix:
continue continue
raise RuntimeError(f'Failed to set parameter {name} to {value} after 3 attempts') raise RuntimeError(f'Failed to set parameter {name} to {value} after 3 attempts')
def set_mode(self, mode: Union[str, int]):
if isinstance(mode, str):
mode = self._modes.index(mode.upper())
self._command_send(mavlink.MAV_CMD_DO_SET_MODE, (0, mode, 0, 0, 0, 0, 0))
def set_position(self, position: List[float], yaw: Optional[float] = None, wait: bool = False, tolerance: float = 0.1): def set_position(self, position: List[float], yaw: Optional[float] = None, wait: bool = False, tolerance: float = 0.1):
raise NotImplementedError('Position control is not implemented yet') raise NotImplementedError('Position control is not implemented yet')
@@ -282,17 +305,37 @@ class Flix:
raise NotImplementedError('Velocity control is not implemented yet') raise NotImplementedError('Velocity control is not implemented yet')
def set_attitude(self, attitude: List[float], thrust: float): def set_attitude(self, attitude: List[float], thrust: float):
raise NotImplementedError('Automatic flight is not implemented yet') if len(attitude) == 3:
attitude = Quaternion([attitude[0], attitude[1], attitude[2]]).q # type: ignore
elif len(attitude) != 4:
raise ValueError('Attitude must be [roll, pitch, yaw] or [w, x, y, z] quaternion')
if not (0 <= thrust <= 1):
raise ValueError('Thrust must be in range [0, 1]')
attitude = self._flu_to_mavlink(attitude)
for _ in range(2): # duplicate to ensure delivery
self.mavlink.set_attitude_target_send(0, self.system_id, 0, 0,
[attitude[0], attitude[1], attitude[2], attitude[3]],
0, 0, 0, thrust)
def set_rates(self, rates: List[float], thrust: float): def set_rates(self, rates: List[float], thrust: float):
raise NotImplementedError('Automatic flight is not implemented yet') if len(rates) != 3:
raise ValueError('Rates must be [roll_rate, pitch_rate, yaw_rate]')
if not (0 <= thrust <= 1):
raise ValueError('Thrust must be in range [0, 1]')
rates = self._flu_to_mavlink(rates)
for _ in range(2): # duplicate to ensure delivery
self.mavlink.set_attitude_target_send(0, self.system_id, 0,
mavlink.ATTITUDE_TARGET_TYPEMASK_ATTITUDE_IGNORE,
[1, 0, 0, 0],
rates[0], rates[1], rates[2], thrust)
def set_motors(self, motors: List[float]): def set_motors(self, motors: List[float]):
if len(motors) != 4: if len(motors) != 4:
raise ValueError('motors must have 4 values') raise ValueError('motors must have 4 values')
if not all(0 <= m <= 1 for m in motors): if not all(0 <= m <= 1 for m in motors):
raise ValueError('motors must be in range [0, 1]') raise ValueError('motors must be in range [0, 1]')
raise NotImplementedError for _ in range(2): # duplicate to ensure delivery
self.mavlink.set_actuator_control_target_send(time.time() * 1000, 0, self.system_id, 0, motors + [0] * 4) # type: ignore
def set_controls(self, roll: float, pitch: float, yaw: float, throttle: float): def set_controls(self, roll: float, pitch: float, yaw: float, throttle: float):
"""Send pilot's controls. Warning: not intended for automatic control""" """Send pilot's controls. Warning: not intended for automatic control"""
@@ -302,9 +345,6 @@ class Flix:
raise ValueError('throttle must be in range [0, 1]') raise ValueError('throttle must be in range [0, 1]')
self.mavlink.manual_control_send(self.system_id, roll * 1000, pitch * 1000, yaw * 1000, throttle * 1000, 0) # type: ignore self.mavlink.manual_control_send(self.system_id, roll * 1000, pitch * 1000, yaw * 1000, throttle * 1000, 0) # type: ignore
def set_mode(self, mode: Literal['MANUAL', 'ACRO', 'STAB', 'USER']):
raise NotImplementedError('Setting mode is not implemented yet')
def cli(self, cmd: str, wait_response: bool = True) -> str: def cli(self, cmd: str, wait_response: bool = True) -> str:
cmd = cmd.strip() cmd = cmd.strip()
if cmd == 'reboot': if cmd == 'reboot':

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"