2 Commits

Author SHA1 Message Date
Oleg Kalachev
82d9d3570d Send only mavlink heartbeats until connected 2025-10-03 07:08:17 +03:00
Oleg Kalachev
d7f8c8d934 Add Wi-Fi client mode
WIFI_AP_MODE define
2025-10-03 06:56:03 +03:00
26 changed files with 137 additions and 168 deletions

View File

@@ -23,19 +23,10 @@ jobs:
with: with:
name: firmware-binary name: firmware-binary
path: flix/build path: flix/build
- name: Build firmware for ESP32-S3 - name: Build firmware without Wi-Fi
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 run: sed -i 's/^#define WIFI_ENABLED 1$/#define WIFI_ENABLED 0/' flix/flix.ino && make
- name: Check c_cpp_properties.json - name: Check c_cpp_properties.json
run: tools/check_c_cpp_properties.py run: tools/check_c_cpp_properties.py
- name: Build for Black Pill F411CE (STM32)
run: |
arduino-cli config set board_manager.additional_urls https://github.com/stm32duino/BoardManagerFiles/raw/main/package_stmicroelectronics_index.json
arduino-cli core install STMicroelectronics:stm32
arduino-cli board listall STMicroelectronics:stm32
arduino-cli lib install "Preferences"
make BOARD=STMicroelectronics:stm32:GenF4:pnum=BLACKPILL_F411CE
build_macos: build_macos:
runs-on: macos-latest runs-on: macos-latest
@@ -62,25 +53,15 @@ jobs:
run: python3 tools/check_c_cpp_properties.py run: python3 tools/check_c_cpp_properties.py
build_simulator: build_simulator:
runs-on: ubuntu-latest runs-on: ubuntu-22.04
container:
image: ubuntu:20.04
steps: 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 - name: Install Arduino CLI
uses: arduino/setup-arduino-cli@v1.1.1 uses: arduino/setup-arduino-cli@v1.1.1
- uses: actions/checkout@v4 - uses: actions/checkout@v4
- name: Install Gazebo - name: Install Gazebo
run: | run: 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
- name: Install SDL2 - name: Install SDL2
run: sudo apt-get install -y libsdl2-dev run: sudo apt-get install libsdl2-dev
- name: Build simulator - name: Build simulator
run: make build_simulator run: make build_simulator
- uses: actions/upload-artifact@v4 - uses: actions/upload-artifact@v4

View File

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

View File

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

View File

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

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): The main loop is running at 1000 Hz. All the dataflow goes through global variables (for simplicity):
* `t` *(float)* — current step time, *s*. * `t` *(double)* — current step time, *s*.
* `dt` *(float)* — time delta between the current and previous steps, *s*. * `dt` *(float)* — time delta between the current and previous steps, *s*.
* `gyro` *(Vector)* — data from the gyroscope, *rad/s*. * `gyro` *(Vector)* — data from the gyroscope, *rad/s*.
* `acc` *(Vector)* — acceleration data from the accelerometer, *m/s<sup>2</sup>*. * `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 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 output.
* **Check the baudrate is correct**. If you see garbage characters in the Serial Monitor, make sure the baudrate is set to 115200. * **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. * **Make sure correct IMU model is chosen**. If using ICM-20948 board, change `MPU9250` to `ICM20948` everywhere 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 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**. * **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. * **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). * `mfl` — should rotate front left motor (clockwise).
* `mrl` — should rotate rear left motor (counter-clockwise). * `mrl` — should rotate rear left motor (counter-clockwise).
* `mrr` — should rotate rear right motor (clockwise). * `mrr` — should rotate rear right motor (clockwise).
* **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. * **Calibrate the RC** if you use it. Type `cr` command in Serial Monitor and follow the instructions.
* If using SBUS receiver, **calibrate the RC**. 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 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. * **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 ### Ubuntu
The latest version of Ubuntu supported by Gazebo 11 simulator is 20.04. If you have a newer version, consider using a virtual machine. The latest version of Ubuntu supported by Gazebo 11 simulator is 22.04. If you have a newer version, consider using a virtual machine.
1. Install Arduino CLI: 1. Install Arduino CLI:
@@ -24,10 +24,7 @@ The latest version of Ubuntu supported by Gazebo 11 simulator is 20.04. If you h
2. Install Gazebo 11: 2. Install Gazebo 11:
```bash ```bash
sudo sh -c 'echo "deb http://packages.osrfoundation.org/gazebo/ubuntu-stable `lsb_release -cs` main" > /etc/apt/sources.list.d/gazebo-stable.list' curl -sSL http://get.gazebosim.org | sh
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: Set up your Gazebo environment variables:

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

@@ -15,7 +15,7 @@
bool mavlinkConnected = false; bool mavlinkConnected = false;
String mavlinkPrintBuffer; String mavlinkPrintBuffer;
extern float controlTime; extern double controlTime;
extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlMode; extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlMode;
void processMavlink() { void processMavlink() {
@@ -26,8 +26,8 @@ void processMavlink() {
void sendMavlink() { void sendMavlink() {
sendMavlinkPrint(); sendMavlinkPrint();
static float lastSlow = 0; static double lastSlow = 0;
static float lastFast = 0; static double lastFast = 0;
mavlink_message_t msg; mavlink_message_t msg;
uint32_t time = t * 1000; uint32_t time = t * 1000;

View File

@@ -25,32 +25,30 @@ const int MOTOR_FRONT_LEFT = 3;
void setupMotors() { void setupMotors() {
print("Setup Motors\n"); print("Setup Motors\n");
#ifdef ESP32
// configure pins
ledcAttach(MOTOR_0_PIN, PWM_FREQUENCY, PWM_RESOLUTION); ledcAttach(MOTOR_0_PIN, PWM_FREQUENCY, PWM_RESOLUTION);
ledcAttach(MOTOR_1_PIN, PWM_FREQUENCY, PWM_RESOLUTION); ledcAttach(MOTOR_1_PIN, PWM_FREQUENCY, PWM_RESOLUTION);
ledcAttach(MOTOR_2_PIN, PWM_FREQUENCY, PWM_RESOLUTION); ledcAttach(MOTOR_2_PIN, PWM_FREQUENCY, PWM_RESOLUTION);
ledcAttach(MOTOR_3_PIN, PWM_FREQUENCY, PWM_RESOLUTION); ledcAttach(MOTOR_3_PIN, PWM_FREQUENCY, PWM_RESOLUTION);
#else
analogWriteResolution(PWM_RESOLUTION);
analogWriteFrequency(PWM_FREQUENCY);
#endif
sendMotors(); sendMotors();
print("Motors initialized\n"); print("Motors initialized\n");
} }
int getDutyCycle(float value) { int getDutyCycle(float value) {
value = constrain(value, 0, 1); value = constrain(value, 0, 1);
float pwm = mapf(value, 0, 1, PWM_MIN, PWM_MAX); float pwm = mapff(value, 0, 1, PWM_MIN, PWM_MAX);
if (value == 0) pwm = PWM_STOP; if (value == 0) pwm = PWM_STOP;
float duty = mapf(pwm, 0, 1000000 / PWM_FREQUENCY, 0, (1 << PWM_RESOLUTION) - 1); float duty = mapff(pwm, 0, 1000000 / PWM_FREQUENCY, 0, (1 << PWM_RESOLUTION) - 1);
return round(duty); return round(duty);
} }
void sendMotors() { void sendMotors() {
analogWrite(MOTOR_0_PIN, getDutyCycle(motors[0])); ledcWrite(MOTOR_0_PIN, getDutyCycle(motors[0]));
analogWrite(MOTOR_1_PIN, getDutyCycle(motors[1])); ledcWrite(MOTOR_1_PIN, getDutyCycle(motors[1]));
analogWrite(MOTOR_2_PIN, getDutyCycle(motors[2])); ledcWrite(MOTOR_2_PIN, getDutyCycle(motors[2]));
analogWrite(MOTOR_3_PIN, getDutyCycle(motors[3])); ledcWrite(MOTOR_3_PIN, getDutyCycle(motors[3]));
} }
bool motorsActive() { bool motorsActive() {

View File

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

View File

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

View File

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

View File

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

View File

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

View File

@@ -6,15 +6,16 @@
#pragma once #pragma once
#include <math.h> #include <math.h>
#ifdef ESP32
#include <soc/soc.h> #include <soc/soc.h>
#include <soc/rtc_cntl_reg.h> #include <soc/rtc_cntl_reg.h>
#endif
const float ONE_G = 9.80665; const float ONE_G = 9.80665;
extern float t;
float mapf(float x, float in_min, float in_max, float out_min, float out_max) { 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;
}
float mapff(float x, float in_min, float in_max, float out_min, float out_max) {
return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min; return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
} }
@@ -39,9 +40,7 @@ float wrapAngle(float angle) {
// Disable reset on low voltage // Disable reset on low voltage
void disableBrownOut() { void disableBrownOut() {
#ifdef ESP32
REG_CLR_BIT(RTC_CNTL_BROWN_OUT_REG, RTC_CNTL_BROWN_OUT_ENA); REG_CLR_BIT(RTC_CNTL_BROWN_OUT_REG, RTC_CNTL_BROWN_OUT_ENA);
#endif
} }
// Trim and split string by spaces // Trim and split string by spaces
@@ -53,23 +52,3 @@ void splitString(String& str, String& token0, String& token1, String& token2) {
token1 = strtok(NULL, " "); // String(NULL) creates empty string token1 = strtok(NULL, " "); // String(NULL) creates empty string
token2 = strtok(NULL, ""); 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

@@ -9,8 +9,11 @@
#include <WiFiAP.h> #include <WiFiAP.h>
#include <WiFiUdp.h> #include <WiFiUdp.h>
#define WIFI_SSID "flix" #define WIFI_AP_MODE 1
#define WIFI_PASSWORD "flixwifi" #define WIFI_AP_SSID "flix"
#define WIFI_AP_PASSWORD "flixwifi"
#define WIFI_SSID ""
#define WIFI_PASSWORD ""
#define WIFI_UDP_PORT 14550 #define WIFI_UDP_PORT 14550
#define WIFI_UDP_REMOTE_PORT 14550 #define WIFI_UDP_REMOTE_PORT 14550
#define WIFI_UDP_REMOTE_ADDR "255.255.255.255" #define WIFI_UDP_REMOTE_ADDR "255.255.255.255"
@@ -19,7 +22,11 @@ WiFiUDP udp;
void setupWiFi() { void setupWiFi() {
print("Setup Wi-Fi\n"); print("Setup Wi-Fi\n");
WiFi.softAP(WIFI_SSID, WIFI_PASSWORD); if (WIFI_AP_MODE) {
WiFi.softAP(WIFI_AP_SSID, WIFI_AP_PASSWORD);
} else {
WiFi.begin(WIFI_SSID, WIFI_PASSWORD);
}
udp.begin(WIFI_UDP_PORT); udp.begin(WIFI_UDP_PORT);
} }

View File

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

View File

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

View File

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

View File

@@ -49,8 +49,6 @@ for configuration in props['configurations']:
print('Check configuration', configuration['name']) print('Check configuration', configuration['name'])
for include_path in configuration.get('includePath', []): 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) check_path(include_path)
for forced_include in configuration.get('forcedInclude', []): for forced_include in configuration.get('forcedInclude', []):