4 Commits

Author SHA1 Message Date
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
8 changed files with 10 additions and 19 deletions

View File

@@ -16,7 +16,7 @@ Do the following:
* **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 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

@@ -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"
@@ -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

@@ -59,6 +59,7 @@ 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},

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: