6 Commits

Author SHA1 Message Date
Oleg Kalachev
67430c7aac Several minor changes 2026-02-02 18:46:36 +03:00
Oleg Kalachev
3631743a29 Drop messages from another systems in pyflix
We shouldn't pass messages where system id != our system id. 
This change may be useful when there are many drones in one network.
2026-02-02 18:28:20 +03:00
Oleg Kalachev
3dde380bb7 Add parameters for list of modes bound to rc switch
Parameters: CTL_FLT_MODE_0, CTL_FLT_MODE_1, CTL_FLT_MODE_2.
Also fix a bug with incorrect choosing the mode from controlMode.
2026-01-27 16:38:20 +03:00
Oleg Kalachev
377b21429b Fix error when launching the sim
Also make the parameters WIFI_LOC_PORT and WIFI_REM_PORT work in the sim.
2026-01-27 16:32:52 +03:00
Oleg Kalachev
1ac443d6f8 Add a build by Arky Matsekh 2026-01-27 15:17:58 +03:00
Oleg Kalachev
964c0f7bc1 Make setting parameter in console printing actual parameter value.
In some cases, it would not be equal to the requested value.
2026-01-27 09:28:01 +03:00
16 changed files with 42 additions and 28 deletions

Binary file not shown.

After

Width:  |  Height:  |  Size: 62 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 48 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 50 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 17 KiB

View File

@@ -143,6 +143,8 @@ If using brushless motors and ESCs:
1. Set the appropriate PWM using the parameters: `MOT_PWM_STOP`, `MOT_PWM_MIN`, and `MOT_PWM_MAX` (1000, 1000, and 2000 is typical).
2. Decrease the PWM frequency using the `MOT_PWM_FREQ` parameter (400 is typical).
Reboot the drone to apply the changes.
> [!CAUTION]
> **Remove the props when configuring the motors!** If improperly configured, you may not be able to stop them.

View File

@@ -4,6 +4,17 @@ This page contains user-built drones based on the Flix project. Publish your pro
---
Author: **Arkadiy "Arky" Matsekh**, Foucault Dynamics, Gold Coast, Australia.<br>
The drone was built for the University of Queensland industry-led Master's capstone project.
**Flight video:**
<a href="https://drive.google.com/file/d/1NNYSVXBY-w0JjCo07D8-PgnVq3ca9plj/view?usp=sharing"><img height=300 src="img/user/arkymatsekh/video.jpg"></a>
<img src="img/user/arkymatsekh/1.jpg" height=150> <img src="img/user/arkymatsekh/2.jpg" height=150> <img src="img/user/arkymatsekh/3.jpg" height=150>
---
Author: [goldarte](https://t.me/goldarte).<br>
<img src="img/user/goldarte/1.jpg" height=150> <img src="img/user/goldarte/2.jpg" height=150>

View File

@@ -52,6 +52,7 @@ PID pitchPID(PITCH_P, PITCH_I, PITCH_D);
PID yawPID(YAW_P, 0, 0);
Vector maxRate(ROLLRATE_MAX, PITCHRATE_MAX, YAWRATE_MAX);
float tiltMax = TILT_MAX;
int flightModes[] = {STAB, STAB, STAB}; // map for rc mode switch
extern const int MOTOR_REAR_LEFT, MOTOR_REAR_RIGHT, MOTOR_FRONT_RIGHT, MOTOR_FRONT_LEFT;
extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlMode;
@@ -65,9 +66,9 @@ void control() {
}
void interpretControls() {
if (controlMode < 0.25) mode = STAB;
if (controlMode < 0.75) mode = STAB;
if (controlMode > 0.75) mode = STAB;
if (controlMode < 0.25) mode = flightModes[0];
else if (controlMode < 0.75) mode = flightModes[1];
else if (controlMode > 0.75) mode = flightModes[2];
if (mode == AUTO) return; // pilot is not effective in AUTO mode

View File

@@ -1,7 +1,7 @@
// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
// Repository: https://github.com/okalachev/flix
// Attitude estimation from gyro and accelerometer
// Attitude estimation using gyro and accelerometer
#include "quaternion.h"
#include "vector.h"

View File

@@ -21,8 +21,8 @@ void setup() {
disableBrownOut();
setupParameters();
setupLED();
setupMotors();
setLED(true);
setupMotors();
setupWiFi();
setupIMU();
setupRC();

View File

@@ -8,12 +8,13 @@
extern float controlTime;
bool mavlinkConnected = false;
String mavlinkPrintBuffer;
int mavlinkSysId = 1;
Rate telemetryFast(10);
Rate telemetrySlow(2);
bool mavlinkConnected = false;
String mavlinkPrintBuffer;
void processMavlink() {
sendMavlink();
receiveMavlink();
@@ -41,9 +42,9 @@ void sendMavlink() {
}
if (telemetryFast && mavlinkConnected) {
const float zeroQuat[] = {0, 0, 0, 0};
const float offset[] = {0, 0, 0, 0};
mavlink_msg_attitude_quaternion_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg,
time, attitude.w, attitude.x, -attitude.y, -attitude.z, rates.x, -rates.y, -rates.z, zeroQuat); // convert to frd
time, attitude.w, attitude.x, -attitude.y, -attitude.z, rates.x, -rates.y, -rates.z, offset); // convert to frd
sendMessage(&msg);
mavlink_msg_rc_channels_raw_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg, controlTime * 1000, 0,

View File

@@ -24,7 +24,6 @@ void setupMotors() {
// configure pins
for (int i = 0; i < 4; i++) {
ledcAttach(motorPins[i], pwmFrequency, pwmResolution);
pwmFrequency = ledcChangeFrequency(motorPins[i], pwmFrequency, pwmResolution); // if re-initializing
}
sendMotors();
print("Motors initialized\n");

View File

@@ -15,9 +15,9 @@ extern float rcLossTimeout, descendTime;
Preferences storage;
struct Parameter {
const char *name; // max length is 15 (Preferences key limit)
const char *name; // max length is 15
bool integer;
union { float *f; int *i; }; // pointer to variable
union { float *f; int *i; }; // pointer to the variable
float cache; // what's stored in flash
Parameter(const char *name, float *variable) : name(name), integer(false), f(variable) {};
Parameter(const char *name, int *variable) : name(name), integer(true), i(variable) {};
@@ -49,6 +49,9 @@ Parameter parameters[] = {
{"CTL_R_RATE_MAX", &maxRate.x},
{"CTL_Y_RATE_MAX", &maxRate.z},
{"CTL_TILT_MAX", &tiltMax},
{"CTL_FLT_MODE_0", &flightModes[0]},
{"CTL_FLT_MODE_1", &flightModes[1]},
{"CTL_FLT_MODE_2", &flightModes[2]},
// imu
{"IMU_ROT_ROLL", &imuRotation.x},
{"IMU_ROT_PITCH", &imuRotation.y},
@@ -109,6 +112,7 @@ Parameter parameters[] = {
};
void setupParameters() {
print("Setup parameters\n");
storage.begin("flix", false);
// Read parameters from storage
for (auto &parameter : parameters) {
@@ -120,11 +124,6 @@ void setupParameters() {
}
}
void afterParameterChange(String name, const float value) {
if (name == "MOT_PWM_FREQ" || name == "MOT_PWM_RES") setupMotors();
if (name == "MOT_PIN_FL" || name == "MOT_PIN_FR" || name == "MOT_PIN_RL" || name == "MOT_PIN_RR") setupMotors();
}
int parametersCount() {
return sizeof(parameters) / sizeof(parameters[0]);
}
@@ -153,7 +152,6 @@ bool setParameter(const char *name, const float value) {
if (strcasecmp(parameter.name, name) == 0) {
if (parameter.integer && !isfinite(value)) return false; // can't set integer to NaN or Inf
parameter.setValue(value);
afterParameterChange(name, value);
return true;
}
}

View File

@@ -165,7 +165,6 @@ void delay(uint32_t ms) {
bool ledcAttach(uint8_t pin, uint32_t freq, uint8_t resolution) { return true; }
bool ledcWrite(uint8_t pin, uint32_t duty) { return true; }
uint32_t ledcChangeFrequency(uint8_t pin, uint32_t freq, uint8_t resolution) { return freq; }
unsigned long __micros;
unsigned long __resetTime = 0;

View File

@@ -9,6 +9,7 @@
#include "quaternion.h"
#include "Arduino.h"
#include "wifi.h"
#include "lpf.h"
extern float t, dt;
extern float controlRoll, controlPitch, controlYaw, controlThrottle, controlMode;
@@ -19,6 +20,7 @@ extern float motors[4];
Vector gyro, acc, imuRotation;
Vector accBias, gyroBias, accScale(1, 1, 1);
LowPassFilter<Vector> gyroBiasFilter(0);
// declarations
void step();

View File

@@ -11,9 +11,10 @@
#include <sys/poll.h>
#include <gazebo/gazebo.hh>
#define WIFI_UDP_PORT 14580
#define WIFI_UDP_REMOTE_PORT 14550
#define WIFI_UDP_REMOTE_ADDR "255.255.255.255"
int wifiMode = 1; // mock
int udpLocalPort = 14580;
int udpRemotePort = 14550;
const char *udpRemoteIP = "255.255.255.255";
int wifiSocket;
@@ -22,22 +23,22 @@ void setupWiFi() {
sockaddr_in addr; // local address
addr.sin_family = AF_INET;
addr.sin_addr.s_addr = INADDR_ANY;
addr.sin_port = htons(WIFI_UDP_PORT);
addr.sin_port = htons(udpLocalPort);
if (bind(wifiSocket, (sockaddr *)&addr, sizeof(addr))) {
gzerr << "Failed to bind WiFi UDP socket on port " << WIFI_UDP_PORT << std::endl;
gzerr << "Failed to bind WiFi UDP socket on port " << udpLocalPort << std::endl;
return;
}
int broadcast = 1;
setsockopt(wifiSocket, SOL_SOCKET, SO_BROADCAST, &broadcast, sizeof(broadcast)); // enable broadcast
gzmsg << "WiFi UDP socket initialized on port " << WIFI_UDP_PORT << " (remote port " << WIFI_UDP_REMOTE_PORT << ")" << std::endl;
gzmsg << "WiFi UDP socket initialized on port " << udpLocalPort << " (remote port " << udpRemotePort << ")" << std::endl;
}
void sendWiFi(const uint8_t *buf, int len) {
if (wifiSocket == 0) setupWiFi();
sockaddr_in addr; // remote address
addr.sin_family = AF_INET;
addr.sin_addr.s_addr = inet_addr(WIFI_UDP_REMOTE_ADDR);
addr.sin_port = htons(WIFI_UDP_REMOTE_PORT);
addr.sin_addr.s_addr = inet_addr(udpRemoteIP);
addr.sin_port = htons(udpRemotePort);
sendto(wifiSocket, buf, len, 0, (sockaddr *)&addr, sizeof(addr));
}

View File

@@ -138,7 +138,7 @@ class Flix:
while True:
try:
msg: Optional[mavlink.MAVLink_message] = self.connection.recv_match(blocking=True)
if msg is None:
if msg is None or msg.get_srcSystem() != self.system_id:
continue
self._connected()
msg_dict = msg.to_dict()