mirror of
https://github.com/okalachev/flix.git
synced 2026-03-30 03:54:20 +00:00
Compare commits
2 Commits
9fd35ba361
...
esp32-c3
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
2308bd4d8f | ||
|
|
8153644578 |
2
.github/workflows/build.yml
vendored
2
.github/workflows/build.yml
vendored
@@ -25,6 +25,8 @@ jobs:
|
||||
path: flix/build
|
||||
- name: Build firmware for ESP32-S3
|
||||
run: make BOARD=esp32:esp32:esp32s3
|
||||
- name: Build firmware for ESP32-C3
|
||||
run: make BOARD=esp32:esp32:esp32c3
|
||||
- name: Check c_cpp_properties.json
|
||||
run: tools/check_c_cpp_properties.py
|
||||
|
||||
|
||||
@@ -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 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*).
|
||||
* **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*).
|
||||
* **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:
|
||||
|
||||
@@ -6,7 +6,6 @@
|
||||
#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;
|
||||
@@ -15,7 +14,6 @@ extern uint16_t channels[16];
|
||||
extern float controlTime;
|
||||
extern int mode;
|
||||
extern bool armed;
|
||||
extern LowPassFilter<Vector> gyroBiasFilter;
|
||||
|
||||
const char* motd =
|
||||
"\nWelcome to\n"
|
||||
@@ -180,7 +178,6 @@ void doCommand(String str, bool echo = false) {
|
||||
#endif
|
||||
} else if (command == "reset") {
|
||||
attitude = Quaternion();
|
||||
gyroBiasFilter.reset();
|
||||
} else if (command == "reboot") {
|
||||
ESP.restart();
|
||||
} else {
|
||||
|
||||
@@ -7,6 +7,7 @@
|
||||
#include "quaternion.h"
|
||||
#include "util.h"
|
||||
|
||||
|
||||
extern float t, dt;
|
||||
extern float controlRoll, controlPitch, controlYaw, controlThrottle, controlMode;
|
||||
extern Vector gyro, acc;
|
||||
|
||||
@@ -19,8 +19,6 @@ 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();
|
||||
@@ -52,6 +50,8 @@ 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);
|
||||
}
|
||||
|
||||
|
||||
14
flix/lpf.h
14
flix/lpf.h
@@ -14,6 +14,15 @@ 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);
|
||||
}
|
||||
|
||||
@@ -22,6 +31,9 @@ public:
|
||||
}
|
||||
|
||||
void reset() {
|
||||
output = T(); // set to zero
|
||||
initialized = false;
|
||||
}
|
||||
|
||||
private:
|
||||
bool initialized = false;
|
||||
};
|
||||
|
||||
@@ -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, getParameter(name), MAV_PARAM_TYPE_REAL32, parametersCount(), 0); // index is unknown
|
||||
m.param_id, m.param_value, MAV_PARAM_TYPE_REAL32, parametersCount(), 0); // index is unknown
|
||||
sendMessage(&msg);
|
||||
}
|
||||
|
||||
|
||||
@@ -59,7 +59,6 @@ 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},
|
||||
|
||||
@@ -6,7 +6,11 @@
|
||||
#include <SBUS.h>
|
||||
#include "util.h"
|
||||
|
||||
#ifdef ESP32C3
|
||||
SBUS rc(Serial1);
|
||||
#else
|
||||
SBUS rc(Serial2);
|
||||
#endif
|
||||
|
||||
uint16_t channels[16]; // raw rc channels
|
||||
float channelZero[16]; // calibration zero values
|
||||
|
||||
@@ -13,7 +13,7 @@ lines = []
|
||||
|
||||
print('Downloading log...')
|
||||
count = 0
|
||||
dev.write('log dump\n'.encode())
|
||||
dev.write('log\n'.encode())
|
||||
while True:
|
||||
line = dev.readline()
|
||||
if not line:
|
||||
|
||||
Reference in New Issue
Block a user