21 Commits

Author SHA1 Message Date
Oleg Kalachev
94fe93020d Remove additional url to install esp32-core from arduino-cli config 2025-10-22 22:00:26 +03:00
Oleg Kalachev
7170b20d1d Simplify command for command handling 2025-10-21 19:41:10 +03:00
Oleg Kalachev
dc9aed113b Minor code fixes 2025-10-21 19:41:05 +03:00
Oleg Kalachev
08b6123eb7 Fixes to troubleshooting 2025-10-21 19:40:54 +03:00
Oleg Kalachev
1a8b63ee04 Send only mavlink heartbeats until connected 2025-10-21 19:39:17 +03:00
Oleg Kalachev
8c49a40516 Skip attitude/rate control if thrustTarget is ineffective
To prevent i term windup.
2025-10-20 23:01:17 +03:00
Oleg Kalachev
ca595edce5 Refactor PID control to simplify the code and modifications
Each PID uses its internal dt, so may be various contexts with different rate.
PID has max dt, so no need to reset explicitly.
2025-10-20 22:54:18 +03:00
KiraFlux
d06eb2a1aa Quaternion::fromBetweenVectors: pass u and v as const references (#21) 2025-10-19 20:46:46 +03:00
Oleg Kalachev
e50a9d5fea Revert t variable type to float instead of double
For the sake of simplicity and consistency.
2025-10-19 20:46:38 +03:00
Oleg Kalachev
ebac78dc0f Minor change 2025-10-19 20:46:26 +03:00
Oleg Kalachev
186cf88d84 Add generic Delay filter 2025-10-19 20:46:11 +03:00
Oleg Kalachev
253aae2220 Lowercase imu and rc variables
To make it more obvious these are variables, not classes.
2025-10-19 20:45:56 +03:00
Oleg Kalachev
6f0964fac4 Rename failsafe.ino to safety.ino
To aggregate all the safety related functionality.
2025-10-19 20:44:54 +03:00
Oleg Kalachev
1d034f268d Add ESP32-S3 build to Actions 2025-10-19 20:44:46 +03:00
Oleg Kalachev
1ca7d32862 Update VSCode settings
Disable error squiggles as they often work incorrectly.
Decrease number of include libraries to index.
2025-10-14 11:43:55 +03:00
Oleg Kalachev
ab941e34fa Fix Gazebo installation
Installation script is deprecated, install using package on Ubuntu 20.04
2025-10-13 18:56:14 +03:00
Oleg Kalachev
7bee3d1751 Improve rc failsafe logic
Don't trigger failsafe if there's no RC at all
Use AUTO mode for descending, instead of STAB
Increase RC loss timeout and descend time
2025-10-12 21:27:08 +03:00
Oleg Kalachev
06ec5f3160 Disarm the drone on simulator plugin reset
In order to reset yaw target.
2025-10-07 15:45:48 +03:00
Oleg Kalachev
c4533e3ac8 Reset yaw target when drone disarmed
Prevent unexpected behavior when the drone tries to restore its old yaw on takeoff.
2025-10-07 15:43:28 +03:00
Oleg Kalachev
e673b50f52 Include FlixPeriph header instead of MPU9250
This simplifies choosing IMU model
2025-10-07 08:43:12 +03:00
Oleg Kalachev
5151bb9133 Ensure showing correct raw data in imu command
Some IMUs will reset acc and gyro buffer on whoAmI() call
2025-10-07 08:43:06 +03:00
25 changed files with 147 additions and 117 deletions

View File

@@ -23,7 +23,9 @@ jobs:
with:
name: firmware-binary
path: flix/build
- name: Build firmware without Wi-Fi
- name: Build firmware for ESP32-S3
run: make BOARD=esp32:esp32:esp32s3
- name: Build firmware with WiFi disabled
run: sed -i 's/^#define WIFI_ENABLED 1$/#define WIFI_ENABLED 0/' flix/flix.ino && make
- name: Check c_cpp_properties.json
run: tools/check_c_cpp_properties.py
@@ -53,15 +55,25 @@ jobs:
run: python3 tools/check_c_cpp_properties.py
build_simulator:
runs-on: ubuntu-22.04
runs-on: ubuntu-latest
container:
image: ubuntu:20.04
steps:
- name: Install dependencies
run: |
apt-get update
DEBIAN_FRONTEND=noninteractive apt-get install -y curl wget build-essential cmake g++ pkg-config gnupg2 lsb-release sudo
- name: Install Arduino CLI
uses: arduino/setup-arduino-cli@v1.1.1
- uses: actions/checkout@v4
- name: Install Gazebo
run: curl -sSL http://get.gazebosim.org | sh
run: |
sudo sh -c 'echo "deb http://packages.osrfoundation.org/gazebo/ubuntu-stable `lsb_release -cs` main" > /etc/apt/sources.list.d/gazebo-stable.list'
wget https://packages.osrfoundation.org/gazebo.key -O - | sudo apt-key add -
sudo apt-get update
sudo apt-get install -y gazebo11 libgazebo11-dev
- name: Install SDL2
run: sudo apt-get install libsdl2-dev
run: sudo apt-get install -y libsdl2-dev
- name: Build simulator
run: make build_simulator
- uses: actions/upload-artifact@v4

View File

@@ -5,13 +5,15 @@
"includePath": [
"${workspaceFolder}/flix",
"${workspaceFolder}/gazebo",
"${workspaceFolder}/tools/**",
"~/.arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32",
"~/.arduino15/packages/esp32/hardware/esp32/3.2.0/libraries/**",
"~/.arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32",
"~/.arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.4-2f7dcd86-v1/esp32/**",
"~/.arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.4-2f7dcd86-v1/esp32/dio_qspi/include",
"~/Arduino/libraries/**",
"/usr/include/**"
"/usr/include/gazebo-11/",
"/usr/include/ignition/math6/"
],
"forcedInclude": [
"${workspaceFolder}/.vscode/intellisense.h",
@@ -51,14 +53,14 @@
"name": "Mac",
"includePath": [
"${workspaceFolder}/flix",
// "${workspaceFolder}/gazebo",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/libraries/**",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32",
"~/Library/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.4-2f7dcd86-v1/esp32/include/**",
"~/Library/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.4-2f7dcd86-v1/esp32/dio_qspi/include",
"~/Documents/Arduino/libraries/**",
"/opt/homebrew/include/**"
"/opt/homebrew/include/gazebo-11/",
"/opt/homebrew/include/ignition/math6/"
],
"forcedInclude": [
"${workspaceFolder}/.vscode/intellisense.h",
@@ -100,6 +102,7 @@
"includePath": [
"${workspaceFolder}/flix",
"${workspaceFolder}/gazebo",
"${workspaceFolder}/tools/**",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/libraries/**",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32",

View File

@@ -1,5 +1,6 @@
{
"C_Cpp.intelliSenseEngineFallback": "enabled",
"C_Cpp.errorSquiggles": "disabled",
"files.associations": {
"*.sdf": "xml",
"*.ino": "cpp",

View File

@@ -87,7 +87,7 @@ The simulator is implemented using Gazebo and runs the original Arduino code:
|Tape, double-sided tape||||
*² — barometer is not used for now.*<br>
*³ — change `MPU9250` to `ICM20948` in `imu.ino` file if using ICM-20948 board.*<br>
*³ — change `MPU9250` to `ICM20948` or `MPU6050` in `imu.ino` file for using the appropriate boards.*<br>
*³⁻¹ — MPU-6050 supports I²C interface only (not recommended). To use it change IMU declaration to `MPU6050 IMU(Wire)`.*<br>
*⁴ — this frame is optimized for GY-91 board, if using other, the board mount holes positions should be modified.*<br>
*⁵ — you also may use any transmitter-receiver pair with SBUS interface.*

View File

@@ -1,5 +1,2 @@
board_manager:
additional_urls:
- https://raw.githubusercontent.com/espressif/arduino-esp32/gh-pages/package_esp32_index.json
network:
connection_timeout: 1h

View File

@@ -8,7 +8,7 @@ The firmware is a regular Arduino sketch, and it follows the classic Arduino one
The main loop is running at 1000 Hz. All the dataflow goes through global variables (for simplicity):
* `t` *(double)* — current step time, *s*.
* `t` *(float)* — current step time, *s*.
* `dt` *(float)* — time delta between the current and previous steps, *s*.
* `gyro` *(Vector)* — data from the gyroscope, *rad/s*.
* `acc` *(Vector)* — acceleration data from the accelerometer, *m/s<sup>2</sup>*.

View File

@@ -15,7 +15,7 @@ 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 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 board, change `MPU9250` to `ICM20948` everywhere in the `imu.ino` file.
* **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*).
* **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.
@@ -32,6 +32,6 @@ Do the following:
* `mfl` — should rotate front left motor (clockwise).
* `mrl` — should rotate rear left motor (counter-clockwise).
* `mrr` — should rotate rear right motor (clockwise).
* **Calibrate the RC** if you use it. Type `cr` command in Serial Monitor and follow the instructions.
* **Check the RC data** if you use it. Use `rc` command, `Control` should show correct values between -1 and 1, and between 0 and 1 for the throttle.
* **Check the remote control**. Using `rc` command, check the control values reflect your sticks movement. All the controls should change between -1 and 1, and throttle between 0 and 1.
* If using SBUS receiver, **calibrate the RC**. Type `cr` command in Serial Monitor and follow the instructions.
* **Check the IMU output using QGroundControl**. Connect to the drone using QGroundControl on your computer. Go to the *Analyze* tab, *MAVLINK Inspector*. Plot the data from the `SCALED_IMU` message. The gyroscope and accelerometer data should change according to the drone movement.

View File

@@ -13,7 +13,7 @@ cd flix
### Ubuntu
The latest version of Ubuntu supported by Gazebo 11 simulator is 22.04. If you have a newer version, consider using a virtual machine.
The latest version of Ubuntu supported by Gazebo 11 simulator is 20.04. If you have a newer version, consider using a virtual machine.
1. Install Arduino CLI:
@@ -24,7 +24,10 @@ The latest version of Ubuntu supported by Gazebo 11 simulator is 22.04. If you h
2. Install Gazebo 11:
```bash
curl -sSL http://get.gazebosim.org | sh
sudo sh -c 'echo "deb http://packages.osrfoundation.org/gazebo/ubuntu-stable `lsb_release -cs` main" > /etc/apt/sources.list.d/gazebo-stable.list'
wget https://packages.osrfoundation.org/gazebo.key -O - | sudo apt-key add -
sudo apt-get update
sudo apt-get install -y gazebo11 libgazebo11-dev
```
Set up your Gazebo environment variables:

View File

@@ -9,8 +9,7 @@
extern const int MOTOR_REAR_LEFT, MOTOR_REAR_RIGHT, MOTOR_FRONT_RIGHT, MOTOR_FRONT_LEFT;
extern const int ACRO, STAB, AUTO;
extern float loopRate, dt;
extern double t;
extern float t, dt, loopRate;
extern uint16_t channels[16];
extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlMode;
extern int mode;
@@ -60,7 +59,7 @@ void print(const char* format, ...) {
}
void pause(float duration) {
double start = t;
float start = t;
while (t - start < duration) {
step();
handleInput();
@@ -75,9 +74,10 @@ void doCommand(String str, bool echo = false) {
// parse command
String command, arg0, arg1;
splitString(str, command, arg0, arg1);
if (command.isEmpty()) return;
// echo command
if (echo && !command.isEmpty()) {
if (echo) {
print("> %s\n", str.c_str());
}
@@ -171,8 +171,6 @@ void doCommand(String str, bool echo = false) {
attitude = Quaternion();
} else if (command == "reboot") {
ESP.restart();
} else if (command == "") {
// do nothing
} else {
print("Invalid command: %s\n", command.c_str());
}

View File

@@ -9,7 +9,6 @@
#include "lpf.h"
#include "util.h"
#define ARMED_THRUST 0.1 // thrust to indicate armed state
#define PITCHRATE_P 0.05
#define PITCHRATE_I 0.2
#define PITCHRATE_D 0.001
@@ -80,7 +79,7 @@ void interpretControls() {
if (mode == STAB) {
float yawTarget = attitudeTarget.getYaw();
if (invalid(yawTarget) || controlYaw != 0) yawTarget = attitude.getYaw(); // reset yaw target if NAN or pilot commands yaw rate
if (!armed || invalid(yawTarget) || controlYaw != 0) yawTarget = attitude.getYaw(); // reset yaw target
attitudeTarget = Quaternion::fromEuler(Vector(controlRoll * tiltMax, controlPitch * tiltMax, yawTarget));
ratesExtra = Vector(0, 0, -controlYaw * maxRate.z); // positive yaw stick means clockwise rotation in FLU
}
@@ -100,12 +99,7 @@ void interpretControls() {
}
void controlAttitude() {
if (!armed || attitudeTarget.invalid()) { // skip attitude control
rollPID.reset();
pitchPID.reset();
yawPID.reset();
return;
}
if (!armed || attitudeTarget.invalid() || thrustTarget < 0.1) return; // skip attitude control
const Vector up(0, 0, 1);
Vector upActual = Quaternion::rotateVector(up, attitude);
@@ -113,28 +107,23 @@ void controlAttitude() {
Vector error = Vector::rotationVectorBetween(upTarget, upActual);
ratesTarget.x = rollPID.update(error.x, dt) + ratesExtra.x;
ratesTarget.y = pitchPID.update(error.y, dt) + ratesExtra.y;
ratesTarget.x = rollPID.update(error.x) + ratesExtra.x;
ratesTarget.y = pitchPID.update(error.y) + ratesExtra.y;
float yawError = wrapAngle(attitudeTarget.getYaw() - attitude.getYaw());
ratesTarget.z = yawPID.update(yawError, dt) + ratesExtra.z;
ratesTarget.z = yawPID.update(yawError) + ratesExtra.z;
}
void controlRates() {
if (!armed || ratesTarget.invalid()) { // skip rates control
rollRatePID.reset();
pitchRatePID.reset();
yawRatePID.reset();
return;
}
if (!armed || ratesTarget.invalid() || thrustTarget < 0.1) return; // skip rates control
Vector error = ratesTarget - rates;
// Calculate desired torque, where 0 - no torque, 1 - maximum possible torque
torqueTarget.x = rollRatePID.update(error.x, dt);
torqueTarget.y = pitchRatePID.update(error.y, dt);
torqueTarget.z = yawRatePID.update(error.z, dt);
torqueTarget.x = rollRatePID.update(error.x);
torqueTarget.y = pitchRatePID.update(error.y);
torqueTarget.z = yawRatePID.update(error.z);
}
void controlTorque() {
@@ -145,12 +134,11 @@ void controlTorque() {
return;
}
if (thrustTarget < 0.05) {
// minimal thrust to indicate armed state
motors[0] = ARMED_THRUST;
motors[1] = ARMED_THRUST;
motors[2] = ARMED_THRUST;
motors[3] = ARMED_THRUST;
if (thrustTarget < 0.1) {
motors[0] = 0.1; // idle thrust
motors[1] = 0.1;
motors[2] = 0.1;
motors[3] = 0.1;
return;
}

View File

@@ -10,7 +10,7 @@
#define SERIAL_BAUDRATE 115200
#define WIFI_ENABLED 1
double t = NAN; // current step time, s
float t = NAN; // current step time, s
float dt; // time delta from previous step, s
float controlRoll, controlPitch, controlYaw, controlThrottle; // pilot's inputs, range [-1, 1]
float controlMode = NAN;

View File

@@ -4,11 +4,12 @@
// Work with the IMU sensor
#include <SPI.h>
#include <MPU9250.h>
#include <FlixPeriph.h>
#include "vector.h"
#include "lpf.h"
#include "util.h"
MPU9250 IMU(SPI);
MPU9250 imu(SPI);
Vector accBias;
Vector accScale(1, 1, 1);
@@ -16,22 +17,22 @@ Vector gyroBias;
void setupIMU() {
print("Setup IMU\n");
IMU.begin();
imu.begin();
configureIMU();
}
void configureIMU() {
IMU.setAccelRange(IMU.ACCEL_RANGE_4G);
IMU.setGyroRange(IMU.GYRO_RANGE_2000DPS);
IMU.setDLPF(IMU.DLPF_MAX);
IMU.setRate(IMU.RATE_1KHZ_APPROX);
IMU.setupInterrupt();
imu.setAccelRange(imu.ACCEL_RANGE_4G);
imu.setGyroRange(imu.GYRO_RANGE_2000DPS);
imu.setDLPF(imu.DLPF_MAX);
imu.setRate(imu.RATE_1KHZ_APPROX);
imu.setupInterrupt();
}
void readIMU() {
IMU.waitForData();
IMU.getGyro(gyro.x, gyro.y, gyro.z);
IMU.getAccel(acc.x, acc.y, acc.z);
imu.waitForData();
imu.getGyro(gyro.x, gyro.y, gyro.z);
imu.getAccel(acc.x, acc.y, acc.z);
calibrateGyroOnce();
// apply scale and bias
acc = (acc - accBias) / accScale;
@@ -49,9 +50,8 @@ void rotateIMU(Vector& data) {
}
void calibrateGyroOnce() {
static float landedTime = 0;
landedTime = landed ? landedTime + dt : 0;
if (landedTime < 2) return; // calibrate only if definitely stationary
static Delay landedDelay(2);
if (!landedDelay.update(landed)) return; // calibrate only if definitely stationary
static LowPassFilter<Vector> gyroCalibrationFilter(0.001);
gyroBias = gyroCalibrationFilter.update(gyro);
@@ -59,7 +59,7 @@ void calibrateGyroOnce() {
void calibrateAccel() {
print("Calibrating accelerometer\n");
IMU.setAccelRange(IMU.ACCEL_RANGE_2G); // the most sensitive mode
imu.setAccelRange(imu.ACCEL_RANGE_2G); // the most sensitive mode
print("1/6 Place level [8 sec]\n");
pause(8);
@@ -93,9 +93,9 @@ void calibrateAccelOnce() {
// Compute the average of the accelerometer readings
acc = Vector(0, 0, 0);
for (int i = 0; i < samples; i++) {
IMU.waitForData();
imu.waitForData();
Vector sample;
IMU.getAccel(sample.x, sample.y, sample.z);
imu.getAccel(sample.x, sample.y, sample.z);
acc = acc + sample;
}
acc = acc / samples;
@@ -119,15 +119,16 @@ void printIMUCalibration() {
}
void printIMUInfo() {
IMU.status() ? print("status: ERROR %d\n", IMU.status()) : print("status: OK\n");
print("model: %s\n", IMU.getModel());
print("who am I: 0x%02X\n", IMU.whoAmI());
imu.status() ? print("status: ERROR %d\n", imu.status()) : print("status: OK\n");
print("model: %s\n", imu.getModel());
print("who am I: 0x%02X\n", imu.whoAmI());
print("rate: %.0f\n", loopRate);
print("gyro: %f %f %f\n", rates.x, rates.y, rates.z);
print("acc: %f %f %f\n", acc.x, acc.y, acc.z);
imu.waitForData();
Vector rawGyro, rawAcc;
IMU.getGyro(rawGyro.x, rawGyro.y, rawGyro.z);
IMU.getAccel(rawAcc.x, rawAcc.y, rawAcc.z);
imu.getGyro(rawGyro.x, rawGyro.y, rawGyro.z);
imu.getAccel(rawAcc.x, rawAcc.y, rawAcc.z);
print("raw gyro: %f %f %f\n", rawGyro.x, rawGyro.y, rawGyro.z);
print("raw acc: %f %f %f\n", rawAcc.x, rawAcc.y, rawAcc.z);
}

View File

@@ -10,7 +10,6 @@
#define LOG_PERIOD 1.0 / LOG_RATE
#define LOG_SIZE LOG_DURATION * LOG_RATE
float tFloat;
Vector attitudeEuler;
Vector attitudeTargetEuler;
@@ -20,7 +19,7 @@ struct LogEntry {
};
LogEntry logEntries[] = {
{"t", &tFloat},
{"t", &t},
{"rates.x", &rates.x},
{"rates.y", &rates.y},
{"rates.z", &rates.z},
@@ -40,7 +39,6 @@ const int logColumns = sizeof(logEntries) / sizeof(logEntries[0]);
float logBuffer[LOG_SIZE][logColumns];
void prepareLogData() {
tFloat = t;
attitudeEuler = attitude.toEuler();
attitudeTargetEuler = attitudeTarget.toEuler();
}
@@ -48,7 +46,7 @@ void prepareLogData() {
void logData() {
if (!armed) return;
static int logPointer = 0;
static double logTime = 0;
static float logTime = 0;
if (t - logTime < LOG_PERIOD) return;
logTime = t;

View File

@@ -12,9 +12,10 @@
#define PERIOD_FAST 0.1
#define MAVLINK_CONTROL_YAW_DEAD_ZONE 0.1f
bool mavlinkConnected = false;
String mavlinkPrintBuffer;
extern double controlTime;
extern float controlTime;
extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlMode;
void processMavlink() {
@@ -25,8 +26,8 @@ void processMavlink() {
void sendMavlink() {
sendMavlinkPrint();
static double lastSlow = 0;
static double lastFast = 0;
static float lastSlow = 0;
static float lastFast = 0;
mavlink_message_t msg;
uint32_t time = t * 1000;
@@ -41,12 +42,14 @@ void sendMavlink() {
mode, MAV_STATE_STANDBY);
sendMessage(&msg);
if (!mavlinkConnected) return; // send only heartbeat until connected
mavlink_msg_extended_sys_state_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,
MAV_VTOL_STATE_UNDEFINED, landed ? MAV_LANDED_STATE_ON_GROUND : MAV_LANDED_STATE_IN_AIR);
sendMessage(&msg);
}
if (t - lastFast >= PERIOD_FAST) {
if (t - lastFast >= PERIOD_FAST && mavlinkConnected) {
lastFast = t;
const float zeroQuat[] = {0, 0, 0, 0};
@@ -80,6 +83,7 @@ void sendMessage(const void *msg) {
void receiveMavlink() {
uint8_t buf[MAVLINK_MAX_PACKET_LEN];
int len = receiveWiFi(buf, MAVLINK_MAX_PACKET_LEN);
if (len) mavlinkConnected = true;
// New packet, parse it
mavlink_message_t msg;

View File

@@ -8,7 +8,6 @@
extern float channelZero[16];
extern float channelMax[16];
extern float rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel;
extern float mavlinkControlScale;
Preferences storage;
@@ -119,7 +118,7 @@ bool setParameter(const char *name, const float value) {
}
void syncParameters() {
static double lastSync = 0;
static float lastSync = 0;
if (t - lastSync < 1) return; // sync once per second
if (motorsActive()) return; // don't use flash while flying, it may cause a delay
lastSync = t;

View File

@@ -9,40 +9,44 @@
class PID {
public:
float p = 0;
float i = 0;
float d = 0;
float windup = 0;
float p, i, d;
float windup;
float dtMax;
float derivative = 0;
float integral = 0;
LowPassFilter<float> lpf; // low pass filter for derivative term
PID(float p, float i, float d, float windup = 0, float dAlpha = 1) : p(p), i(i), d(d), windup(windup), lpf(dAlpha) {};
PID(float p, float i, float d, float windup = 0, float dAlpha = 1, float dtMax = 0.1) :
p(p), i(i), d(d), windup(windup), lpf(dAlpha), dtMax(dtMax) {}
float update(float error, float dt) {
integral += error * dt;
float update(float error) {
float dt = t - prevTime;
if (isfinite(prevError) && dt > 0) {
// calculate derivative if both dt and prevError are valid
derivative = (error - prevError) / dt;
// apply low pass filter to derivative
derivative = lpf.update(derivative);
if (dt > 0 && dt < dtMax) {
integral += error * dt;
derivative = lpf.update((error - prevError) / dt); // compute derivative and apply low-pass filter
} else {
integral = 0;
derivative = 0;
}
prevError = error;
prevTime = t;
return p * error + constrain(i * integral, -windup, windup) + d * derivative; // PID
}
void reset() {
prevError = NAN;
prevTime = NAN;
integral = 0;
derivative = 0;
lpf.reset();
}
private:
float prevError = NAN;
float prevTime = NAN;
};

View File

@@ -45,7 +45,7 @@ public:
cx * cy * sz - sx * sy * cz);
}
static Quaternion fromBetweenVectors(Vector u, Vector v) {
static Quaternion fromBetweenVectors(const Vector& u, const Vector& v) {
float dot = u.x * v.x + u.y * v.y + u.z * v.z;
float w1 = u.y * v.z - u.z * v.y;
float w2 = u.z * v.x - u.x * v.z;

View File

@@ -6,10 +6,10 @@
#include <SBUS.h>
#include "util.h"
SBUS RC(Serial2); // NOTE: Use RC(Serial2, 16, 17) if you use the old UART2 pins
SBUS rc(Serial2); // NOTE: Use RC(Serial2, 16, 17) if you use the old UART2 pins
uint16_t channels[16]; // raw rc channels
double controlTime; // time of the last controls update
float controlTime; // time of the last controls update
float channelZero[16]; // calibration zero values
float channelMax[16]; // calibration max values
@@ -18,12 +18,12 @@ float rollChannel = NAN, pitchChannel = NAN, throttleChannel = NAN, yawChannel =
void setupRC() {
print("Setup RC\n");
RC.begin();
rc.begin();
}
bool readRC() {
if (RC.read()) {
SBUSData data = RC.data();
if (rc.read()) {
SBUSData data = rc.data();
for (int i = 0; i < 16; i++) channels[i] = data.ch[i]; // copy channels data
normalizeRC();
controlTime = t;

View File

@@ -3,10 +3,10 @@
// Fail-safe functions
#define RC_LOSS_TIMEOUT 0.5
#define DESCEND_TIME 3.0 // time to descend from full throttle to zero
#define RC_LOSS_TIMEOUT 1
#define DESCEND_TIME 10
extern double controlTime;
extern float controlTime;
extern float controlRoll, controlPitch, controlThrottle, controlYaw;
void failsafe() {
@@ -16,7 +16,7 @@ void failsafe() {
// RC loss failsafe
void rcLossFailsafe() {
if (mode == AUTO) return;
if (controlTime == 0) return; // no RC at all
if (!armed) return;
if (t - controlTime > RC_LOSS_TIMEOUT) {
descend();
@@ -25,14 +25,12 @@ void rcLossFailsafe() {
// Smooth descend on RC lost
void descend() {
mode = STAB;
controlRoll = 0;
controlPitch = 0;
controlYaw = 0;
controlThrottle -= dt / DESCEND_TIME;
if (controlThrottle < 0) {
mode = AUTO;
attitudeTarget = Quaternion();
thrustTarget -= dt / DESCEND_TIME;
if (thrustTarget < 0) {
thrustTarget = 0;
armed = false;
controlThrottle = 0;
}
}

View File

@@ -6,7 +6,7 @@
float loopRate; // Hz
void step() {
double now = micros() / 1000000.0;
float now = micros() / 1000000.0;
dt = now - t;
t = now;
@@ -18,7 +18,7 @@ void step() {
}
void computeLoopRate() {
static double windowStart = 0;
static float windowStart = 0;
static uint32_t rate = 0;
rate++;
if (t - windowStart >= 1) { // 1 second window

View File

@@ -10,6 +10,7 @@
#include <soc/rtc_cntl_reg.h>
const float ONE_G = 9.80665;
extern float t;
float mapf(long x, long in_min, long in_max, float out_min, float out_max) {
return (float)(x - in_min) * (out_max - out_min) / (float)(in_max - in_min) + out_min;
@@ -52,3 +53,23 @@ void splitString(String& str, String& token0, String& token1, String& token2) {
token1 = strtok(NULL, " "); // String(NULL) creates empty string
token2 = strtok(NULL, "");
}
// Delay filter for boolean signals - ensures the signal is on for at least 'delay' seconds
class Delay {
public:
float delay;
float start = NAN;
Delay(float delay) : delay(delay) {}
bool update(bool on) {
if (!on) {
start = NAN;
return false;
}
if (isnan(start)) {
start = t;
}
return t - start >= delay;
}
};

View File

@@ -1,7 +1,7 @@
cmake_minimum_required(VERSION 3.5 FATAL_ERROR)
project(flix_gazebo)
# === gazebo plugin
# Gazebo plugin
find_package(gazebo REQUIRED)
find_package(SDL2 REQUIRED)
include_directories(${GAZEBO_INCLUDE_DIRS})

View File

@@ -12,7 +12,7 @@
#define WIFI_ENABLED 1
double t = NAN;
float t = NAN;
float dt;
float motors[4];
float controlRoll, controlPitch, controlYaw, controlThrottle = NAN;

View File

@@ -21,7 +21,7 @@
#include "cli.ino"
#include "control.ino"
#include "estimate.ino"
#include "failsafe.ino"
#include "safety.ino"
#include "log.ino"
#include "lpf.h"
#include "mavlink.ino"
@@ -59,6 +59,7 @@ public:
void OnReset() {
attitude = Quaternion(); // reset estimated attitude
armed = false;
__resetTime += __micros;
gzmsg << "Flix plugin reset" << endl;
}

View File

@@ -49,6 +49,8 @@ for configuration in props['configurations']:
print('Check configuration', configuration['name'])
for include_path in configuration.get('includePath', []):
if include_path.startswith('/opt/') or include_path.startswith('/usr/'): # don't check non-Arduino libs
continue
check_path(include_path)
for forced_include in configuration.get('forcedInclude', []):