7 Commits

Author SHA1 Message Date
Oleg Kalachev
6c41f65ef9 Apply motors configuration without reboot 2026-01-27 09:56:39 +03:00
Oleg Kalachev
40bdaacedb Make motor subsystem configurable using parameters
Motor pins: MOT_PIN_FL, MOT_PIN_FR, MOT_PIN_RL, MOT_PIN_RR.
PWM configuration: MOT_PWM_FREQ, MOT_PWM_RES, MOT_PWM_STOP, MOT_PWM_MIN, MOT_PWM_MAX.
MOT_PWM_MAX = -1 chooses duty cycle mode for brushed motors (default).
2026-01-27 08:40:52 +03:00
Oleg Kalachev
7d74f3d5cd Minor docs fixes 2026-01-27 07:21:21 +03:00
Oleg Kalachev
9fd35ba361 Simplify lpf filter code
Begin with zero instead of the initializing value, as the latter doesn't make much sense in practice, but complicates the code much.
2026-01-24 09:43:46 +03:00
Oleg Kalachev
ca50f75576 Various minor fixes 2026-01-24 09:34:16 +03:00
Oleg Kalachev
e47a31f981 Fix mavlink parameter set acknowledgement value
If the parameter is integer the acknowledgement should contain the rounded value.
2026-01-24 09:32:49 +03:00
Oleg Kalachev
7ad3022798 Add parameter for configuring gyro bias lpf
+ reset the filter on `reset` command
2026-01-24 09:31:32 +03:00
17 changed files with 98 additions and 85 deletions

View File

@@ -138,10 +138,10 @@ You can see a user-contributed [variant of complete circuit diagram](https://mir
|Motor|Position|Direction|Prop type|Motor wires|GPIO|
|-|-|-|-|-|-|
|Motor 0|Rear left|Counter-clockwise|B|Black & White|GPIO12 (*TDI*)|
|Motor 1|Rear right|Clockwise|A|Blue & Red|GPIO13 (*TCK*)|
|Motor 2|Front right|Counter-clockwise|B|Black & White|GPIO14 (*TMS*)|
|Motor 3|Front left|Clockwise|A|Blue & Red|GPIO15 (*TD0*)|
|Motor 0|Rear left|Counter-clockwise|B|Black & White|GPIO12 *(TDI)*|
|Motor 1|Rear right|Clockwise|A|Blue & Red|GPIO13 *(TCK)*|
|Motor 2|Front right|Counter-clockwise|B|Black & White|GPIO14 *(TMS)*|
|Motor 3|Front left|Clockwise|A|Blue & Red|GPIO15 *(TD0)*|
Clockwise motors have blue & red wires and correspond to propeller type A (marked on the propeller).
Counter-clockwise motors have black & white wires correspond to propeller type B.

View File

@@ -41,10 +41,10 @@ Motors connection table:
|Motor|Position|Direction|Prop type|Motor wires|GPIO|
|-|-|-|-|-|-|
|Motor 0|Rear left|Counter-clockwise|B|Black & White|GPIO12 (*TDI*)|
|Motor 1|Rear right|Clockwise|A|Blue & Red|GPIO13 (*TCK*)|
|Motor 2|Front right|Counter-clockwise|B|Black & White|GPIO14 (*TMS*)|
|Motor 3|Front left|Clockwise|A|Blue & Red|GPIO15 (*TD0*)|
|Motor 0|Rear left|Counter-clockwise|B|Black & White|GPIO12 *(TDI)*|
|Motor 1|Rear right|Clockwise|A|Blue & Red|GPIO13 *(TCK)*|
|Motor 2|Front right|Counter-clockwise|B|Black & White|GPIO14 *(TMS)*|
|Motor 3|Front left|Clockwise|A|Blue & Red|GPIO15 *(TD0)*|
## Motors tightening

View File

@@ -110,7 +110,7 @@ float angle = Vector::angleBetween(a, b); // 1.57 (90 градусов)
#### Скалярное произведение
Скалярное произведение векторов (*dot product*) — это произведение длин двух векторов на косинус угла между ними. В математике оно обозначается знаком `·` или слитным написанием векторов. Интуитивно, результат скалярного произведения показывает, насколько два вектора *сонаправлены*.
Скалярное произведение векторов *(dot product)* — это произведение длин двух векторов на косинус угла между ними. В математике оно обозначается знаком `·` или слитным написанием векторов. Интуитивно, результат скалярного произведения показывает, насколько два вектора *сонаправлены*.
В Flix используется статический метод `Vector::dot()`:
@@ -124,7 +124,7 @@ float dotProduct = Vector::dot(a, b); // 32
#### Векторное произведение
Векторное произведение (*cross product*) позволяет найти вектор, перпендикулярный двум другим векторам. В математике оно обозначается знаком `×`, а в прошивке используется статический метод `Vector::cross()`:
Векторное произведение *(cross product)* позволяет найти вектор, перпендикулярный двум другим векторам. В математике оно обозначается знаком `×`, а в прошивке используется статический метод `Vector::cross()`:
```cpp
Vector a(1, 2, 3);
@@ -144,9 +144,9 @@ Vector crossProduct = Vector::cross(a, b); // -3, 6, -3
В прошивке углы Эйлера сохраняются в обычный объект `Vector` (хоть и, строго говоря, не являются вектором):
* Угол по крену (*roll*) — `vector.x`.
* Угол по тангажу (*pitch*) — `vector.y`.
* Угол по рысканию (*yaw*) — `vector.z`.
* Угол по крену *(roll)* — `vector.x`.
* Угол по тангажу *(pitch)* — `vector.y`.
* Угол по рысканию *(yaw)* — `vector.z`.
Особенности углов Эйлера:
@@ -162,8 +162,8 @@ Vector crossProduct = Vector::cross(a, b); // -3, 6, -3
Помимо углов Эйлера, любую ориентацию в трехмерном пространстве можно представить в виде вращения вокруг некоторой оси на некоторый угол. В геометрии это доказывается, как **теорема вращения Эйлера**. В таком представлении ориентация задается двумя величинами:
* **Ось вращения** (*axis*) — единичный вектор, определяющий ось вращения.
* **Угол поворота** (*angle* или *θ*) — угол, на который нужно повернуть объект вокруг этой оси.
* **Ось вращения** *(axis)* — единичный вектор, определяющий ось вращения.
* **Угол поворота** *(angle* или *θ)* — угол, на который нужно повернуть объект вокруг этой оси.
В Flix ось вращения задается объектом `Vector`, а угол поворота — числом типа `float` в радианах:
@@ -177,7 +177,7 @@ float angle = radians(45);
### Вектор вращения
Если умножить вектор *axis* на угол поворота *θ*, то получится **вектор вращения** (*rotation vector*). Этот вектор играет важную роль в алгоритмах управления ориентацией летательного аппарата.
Если умножить вектор *axis* на угол поворота *θ*, то получится **вектор вращения** *(rotation vector)*. Этот вектор играет важную роль в алгоритмах управления ориентацией летательного аппарата.
Вектор вращения обладает замечательным свойством: если угловые скорости объекта (в собственной системе координат) в каждый момент времени совпадают с компонентами этого вектора, то за единичное время объект придет к заданной этим вектором ориентации. Это свойство позволяет использовать вектор вращения для управления ориентацией объекта посредством управления угловыми скоростями.
@@ -198,7 +198,7 @@ Vector rotation = radians(45) * Vector(1, 2, 3);
<a href="https://github.com/okalachev/flix/blob/master/flix/quaternion.h"><code>quaternion.h</code></a>.<br>
</div>
Вектор вращения удобен, но еще удобнее использовать **кватернион**. В Flix кватернионы задаются объектами `Quaternion` из библиотеки `quaternion.h`. Кватернион состоит из четырех значений: *w*, *x*, *y*, *z* и рассчитывается из вектора оси вращения (*axis*) и угла поворота (*θ*) по формуле:
Вектор вращения удобен, но еще удобнее использовать **кватернион**. В Flix кватернионы задаются объектами `Quaternion` из библиотеки `quaternion.h`. Кватернион состоит из четырех значений: *w*, *x*, *y*, *z* и рассчитывается из вектора оси вращения *(axis)* и угла поворота *(θ)* по формуле:
\\[ q = \left( \begin{array}{c} w \\\\ x \\\\ y \\\\ z \end{array} \right) = \left( \begin{array}{c} \cos\left(\frac{\theta}{2}\right) \\\\ axis\_x \cdot \sin\left(\frac{\theta}{2}\right) \\\\ axis\_y \cdot \sin\left(\frac{\theta}{2}\right) \\\\ axis\_z \cdot \sin\left(\frac{\theta}{2}\right) \end{array} \right) \\]

View File

@@ -177,7 +177,7 @@ imu.setDLPF(imu.DLPF_MAX);
## Калибровка гироскопа
Как и любое измерительное устройство, гироскоп вносит искажения в измерения. Наиболее простая модель этих искажений делит их на статические смещения (*bias*) и случайный шум (*noise*):
Как и любое измерительное устройство, гироскоп вносит искажения в измерения. Наиболее простая модель этих искажений делит их на статические смещения *(bias)* и случайный шум *(noise)*:
\\[ gyro_{xyz}=rates_{xyz}+bias_{xyz}+noise \\]

View File

@@ -13,10 +13,10 @@ Do the following:
Do the following:
* **Check the battery voltage**. Use a multimeter to measure the battery voltage. It should be in range of 3.7-4.2 V.
* **Check if there are some startup errors**. Connect the ESP32 to the computer and check the Serial Monitor output. Use the Reset button to make sure you see the whole ESP32 output.
* **Check if there are some startup errors**. Connect the ESP32 to the computer and check the Serial Monitor output. Use the Reset button to make sure you see the whole ESP32 startup output.
* **Check the baudrate is correct**. If you see garbage characters in the Serial Monitor, make sure the baudrate is set to 115200.
* **Make sure correct IMU model is chosen**. If using ICM-20948/MPU-6050 board, change `MPU9250` to `ICM20948`/`MPU6050` in the `imu.ino` file.
* **Check if the CLI is working**. Perform `help` command in Serial Monitor. You should see the list of available commands. You can also access the CLI using QGroundControl (*Vehicle Setup**Analyze Tools**MAVLink Console*).
* **Check if the console is working**. Perform `help` command in Serial Monitor. You should see the list of available commands. You can also access the console using QGroundControl *(Vehicle Setup**Analyze Tools**MAVLink Console)*.
* **Configure QGroundControl correctly before connecting to the drone** if you use it to control the drone. Go to the settings and enable *Virtual Joystick*. *Auto-Center Throttle* setting **should be disabled**.
* **If QGroundControl doesn't connect**, you might need to disable the firewall and/or VPN on your computer.
* **Check the IMU is working**. Perform `imu` command and check its output:

View File

@@ -134,6 +134,18 @@ Before flight you need to calibrate the accelerometer:
1. Access the console using QGroundControl (recommended) or Serial Monitor.
2. Type `ca` command there and follow the instructions.
### Setup motors
If using non-default motor pins, set the pin numbers using the parameters: `MOTOR_PIN_FL`, `MOTOR_PIN_FR`, `MOTOR_PIN_RL`, `MOTOR_PIN_RR` (front-left, front-right, rear-left, rear-right respectively).
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).
> [!CAUTION]
> **Remove the props when configuring the motors!** If improperly configured, you may not be able to stop them.
### Check everything works
1. Check the IMU is working: perform `imu` command and check its output:
@@ -250,8 +262,8 @@ You can configure the Wi-Fi using parameters and console commands.
The Wi-Fi mode is chosen using `WIFI_MODE` parameter in QGroundControl or in the console:
* `0` — Wi-Fi is disabled.
* `1` — Access Point mode (*AP*) the drone creates a Wi-Fi network.
* `2` — Client mode (*STA*) — the drone connects to an existing Wi-Fi network.
* `1` — Access Point mode *(AP)* the drone creates a Wi-Fi network.
* `2` — Client mode *(STA)* the drone connects to an existing Wi-Fi network.
* `3` — *ESP-NOW (not implemented yet)*.
> [!WARNING]

View File

@@ -6,6 +6,7 @@
#include "pid.h"
#include "vector.h"
#include "util.h"
#include "lpf.h"
extern const int MOTOR_REAR_LEFT, MOTOR_REAR_RIGHT, MOTOR_FRONT_RIGHT, MOTOR_FRONT_LEFT;
extern const int RAW, ACRO, STAB, AUTO;
@@ -14,6 +15,7 @@ extern uint16_t channels[16];
extern float controlTime;
extern int mode;
extern bool armed;
extern LowPassFilter<Vector> gyroBiasFilter;
const char* motd =
"\nWelcome to\n"
@@ -92,7 +94,7 @@ void doCommand(String str, bool echo = false) {
} else if (command == "p") {
bool success = setParameter(arg0.c_str(), arg1.toFloat());
if (success) {
print("%s = %g\n", arg0.c_str(), arg1.toFloat());
print("%s = %g\n", arg0.c_str(), getParameter(arg0.c_str()));
} else {
print("Parameter not found: %s\n", arg0.c_str());
}
@@ -178,6 +180,7 @@ void doCommand(String str, bool echo = false) {
#endif
} else if (command == "reset") {
attitude = Quaternion();
gyroBiasFilter.reset();
} else if (command == "reboot") {
ESP.restart();
} else {

View File

@@ -7,7 +7,6 @@
#include "quaternion.h"
#include "util.h"
extern float t, dt;
extern float controlRoll, controlPitch, controlYaw, controlThrottle, controlMode;
extern Vector gyro, acc;

View File

@@ -19,6 +19,8 @@ Vector acc; // accelerometer output, m/s/s
Vector accBias;
Vector accScale(1, 1, 1);
LowPassFilter<Vector> gyroBiasFilter(0.001);
void setupIMU() {
print("Setup IMU\n");
imu.begin();
@@ -50,8 +52,6 @@ void readIMU() {
void calibrateGyroOnce() {
static Delay landedDelay(2);
if (!landedDelay.update(landed)) return; // calibrate only if definitely stationary
static LowPassFilter<Vector> gyroBiasFilter(0.001);
gyroBias = gyroBiasFilter.update(gyro);
}

View File

@@ -14,15 +14,6 @@ public:
LowPassFilter(float alpha): alpha(alpha) {};
T update(const T input) {
if (alpha == 1) { // filter disabled
return input;
}
if (!initialized) {
output = input;
initialized = true;
}
return output += alpha * (input - output);
}
@@ -31,9 +22,6 @@ public:
}
void reset() {
initialized = false;
output = T(); // set to zero
}
private:
bool initialized = false;
};

View File

@@ -142,7 +142,7 @@ void handleMavlink(const void *_msg) {
// send ack
mavlink_message_t msg;
mavlink_msg_param_value_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg,
m.param_id, m.param_value, MAV_PARAM_TYPE_REAL32, parametersCount(), 0); // index is unknown
m.param_id, getParameter(name), MAV_PARAM_TYPE_REAL32, parametersCount(), 0); // index is unknown
sendMessage(&msg);
}

View File

@@ -1,24 +1,19 @@
// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
// Repository: https://github.com/okalachev/flix
// Motors output control using MOSFETs
// In case of using ESCs, change PWM_STOP, PWM_MIN and PWM_MAX to appropriate values in μs, decrease PWM_FREQUENCY (to 400)
// PWM control for motors
#include "util.h"
#define MOTOR_0_PIN 12 // rear left
#define MOTOR_1_PIN 13 // rear right
#define MOTOR_2_PIN 14 // front right
#define MOTOR_3_PIN 15 // front left
#define PWM_FREQUENCY 78000
#define PWM_RESOLUTION 10
#define PWM_STOP 0
#define PWM_MIN 0
#define PWM_MAX 1000000 / PWM_FREQUENCY
float motors[4]; // normalized motor thrusts in range [0..1]
int motorPins[4] = {12, 13, 14, 15}; // default pin numbers
int pwmFrequency = 78000;
int pwmResolution = 10;
int pwmStop = 0;
int pwmMin = 0;
int pwmMax = -1; // -1 means duty cycle mode
const int MOTOR_REAR_LEFT = 0;
const int MOTOR_REAR_RIGHT = 1;
const int MOTOR_FRONT_RIGHT = 2;
@@ -26,30 +21,31 @@ const int MOTOR_FRONT_LEFT = 3;
void setupMotors() {
print("Setup Motors\n");
// configure pins
ledcAttach(MOTOR_0_PIN, PWM_FREQUENCY, PWM_RESOLUTION);
ledcAttach(MOTOR_1_PIN, PWM_FREQUENCY, PWM_RESOLUTION);
ledcAttach(MOTOR_2_PIN, PWM_FREQUENCY, PWM_RESOLUTION);
ledcAttach(MOTOR_3_PIN, PWM_FREQUENCY, PWM_RESOLUTION);
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");
}
int getDutyCycle(float value) {
value = constrain(value, 0, 1);
float pwm = mapf(value, 0, 1, PWM_MIN, PWM_MAX);
if (value == 0) pwm = PWM_STOP;
float duty = mapf(pwm, 0, 1000000 / PWM_FREQUENCY, 0, (1 << PWM_RESOLUTION) - 1);
return round(duty);
void sendMotors() {
for (int i = 0; i < 4; i++) {
ledcWrite(motorPins[i], getDutyCycle(motors[i]));
}
}
void sendMotors() {
ledcWrite(MOTOR_0_PIN, getDutyCycle(motors[0]));
ledcWrite(MOTOR_1_PIN, getDutyCycle(motors[1]));
ledcWrite(MOTOR_2_PIN, getDutyCycle(motors[2]));
ledcWrite(MOTOR_3_PIN, getDutyCycle(motors[3]));
int getDutyCycle(float value) {
value = constrain(value, 0, 1);
if (pwmMax >= 0) { // pwm mode
float pwm = mapf(value, 0, 1, pwmMin, pwmMax);
if (value == 0) pwm = pwmStop;
float duty = mapf(pwm, 0, 1000000 / pwmFrequency, 0, (1 << pwmResolution) - 1);
return round(duty);
} else { // duty cycle mode
return round(value * ((1 << pwmResolution) - 1));
}
}
bool motorsActive() {

View File

@@ -59,9 +59,20 @@ Parameter parameters[] = {
{"IMU_ACC_SCALE_X", &accScale.x},
{"IMU_ACC_SCALE_Y", &accScale.y},
{"IMU_ACC_SCALE_Z", &accScale.z},
{"IMU_GYRO_BIAS_A", &gyroBiasFilter.alpha},
// estimate
{"EST_ACC_WEIGHT", &accWeight},
{"EST_RATES_LPF_A", &ratesFilter.alpha},
// motors
{"MOT_PIN_FL", &motorPins[MOTOR_FRONT_LEFT]},
{"MOT_PIN_FR", &motorPins[MOTOR_FRONT_RIGHT]},
{"MOT_PIN_RL", &motorPins[MOTOR_REAR_LEFT]},
{"MOT_PIN_RR", &motorPins[MOTOR_REAR_RIGHT]},
{"MOT_PWM_FREQ", &pwmFrequency},
{"MOT_PWM_RES", &pwmResolution},
{"MOT_PWM_STOP", &pwmStop},
{"MOT_PWM_MIN", &pwmMin},
{"MOT_PWM_MAX", &pwmMax},
// rc
{"RC_ZERO_0", &channelZero[0]},
{"RC_ZERO_1", &channelZero[1]},
@@ -109,6 +120,11 @@ 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]);
}
@@ -137,6 +153,7 @@ 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,6 +165,7 @@ 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

@@ -32,6 +32,7 @@ void controlRates();
void controlTorque();
const char* getModeName();
void sendMotors();
int getDutyCycle(float value);
bool motorsActive();
void testMotor(int n);
void print(const char* format, ...);

View File

@@ -13,7 +13,7 @@ lines = []
print('Downloading log...')
count = 0
dev.write('log\n'.encode())
dev.write('log dump\n'.encode())
while True:
line = dev.readline()
if not line:

View File

@@ -92,17 +92,17 @@ Full list of events:
|-----|-----------|----------------|
|`connected`|Connected to the drone||
|`disconnected`|Connection is lost||
|`armed`|Armed state update|Armed state (*bool*)|
|`mode`|Flight mode update|Flight mode (*str*)|
|`landed`|Landed state update|Landed state (*bool*)|
|`armed`|Armed state update|Armed state *(bool)*|
|`mode`|Flight mode update|Flight mode *(str)*|
|`landed`|Landed state update|Landed state *(bool)*|
|`print`|The drone prints text to the console|Text|
|`attitude`|Attitude update|Attitude quaternion (*list*)|
|`attitude_euler`|Attitude update|Euler angles (*list*)|
|`rates`|Angular rates update|Angular rates (*list*)|
|`channels`|Raw RC channels update|Raw RC channels (*list*)|
|`motors`|Motor outputs update|Motor outputs (*list*)|
|`acc`|Accelerometer update|Accelerometer output (*list*)|
|`gyro`|Gyroscope update|Gyroscope output (*list*)|
|`attitude`|Attitude update|Attitude quaternion *(list)*|
|`attitude_euler`|Attitude update|Euler angles *(list)*|
|`rates`|Angular rates update|Angular rates *(list)*|
|`channels`|Raw RC channels update|Raw RC channels *(list)*|
|`motors`|Motor outputs update|Motor outputs *(list)*|
|`acc`|Accelerometer update|Accelerometer output *(list)*|
|`gyro`|Gyroscope update|Gyroscope output *(list)*|
|`mavlink`|Received MAVLink message|Message object|
|`mavlink.<message_name>`|Received specific MAVLink message|Message object|
|`mavlink.<message_id>`|Received specific MAVLink message|Message object|
@@ -277,7 +277,3 @@ logger = logging.getLogger('flix')
logger.setLevel(logging.DEBUG) # be more verbose
logger.setLevel(logging.WARNING) # be less verbose
```
## Stability
The library is in development stage. The API is not stable.