mirror of
https://github.com/okalachev/flix.git
synced 2026-01-11 13:36:43 +00:00
Compare commits
9 Commits
e59a190c1c
...
stm
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
c3b818c2ae | ||
|
|
531b3f4d04 | ||
|
|
795b248b94 | ||
|
|
77c4b5fc5b | ||
|
|
1a017ccb97 | ||
|
|
7170b20d1d | ||
|
|
dc9aed113b | ||
|
|
08b6123eb7 | ||
|
|
1a8b63ee04 |
7
.github/workflows/build.yml
vendored
7
.github/workflows/build.yml
vendored
@@ -29,6 +29,13 @@ jobs:
|
||||
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
|
||||
- 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:
|
||||
runs-on: macos-latest
|
||||
|
||||
45
.vscode/c_cpp_properties.json
vendored
45
.vscode/c_cpp_properties.json
vendored
@@ -18,7 +18,20 @@
|
||||
"forcedInclude": [
|
||||
"${workspaceFolder}/.vscode/intellisense.h",
|
||||
"~/.arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32/Arduino.h",
|
||||
"~/.arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32/pins_arduino.h"
|
||||
"~/.arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32/pins_arduino.h",
|
||||
"${workspaceFolder}/flix/cli.ino",
|
||||
"${workspaceFolder}/flix/control.ino",
|
||||
"${workspaceFolder}/flix/estimate.ino",
|
||||
"${workspaceFolder}/flix/flix.ino",
|
||||
"${workspaceFolder}/flix/imu.ino",
|
||||
"${workspaceFolder}/flix/led.ino",
|
||||
"${workspaceFolder}/flix/log.ino",
|
||||
"${workspaceFolder}/flix/mavlink.ino",
|
||||
"${workspaceFolder}/flix/motors.ino",
|
||||
"${workspaceFolder}/flix/rc.ino",
|
||||
"${workspaceFolder}/flix/time.ino",
|
||||
"${workspaceFolder}/flix/wifi.ino",
|
||||
"${workspaceFolder}/flix/parameters.ino"
|
||||
],
|
||||
"compilerPath": "~/.arduino15/packages/esp32/tools/esp-x32/2411/bin/xtensa-esp32-elf-g++",
|
||||
"cStandard": "c11",
|
||||
@@ -52,7 +65,20 @@
|
||||
"forcedInclude": [
|
||||
"${workspaceFolder}/.vscode/intellisense.h",
|
||||
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32/Arduino.h",
|
||||
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32/pins_arduino.h"
|
||||
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32/pins_arduino.h",
|
||||
"${workspaceFolder}/flix/flix.ino",
|
||||
"${workspaceFolder}/flix/cli.ino",
|
||||
"${workspaceFolder}/flix/control.ino",
|
||||
"${workspaceFolder}/flix/estimate.ino",
|
||||
"${workspaceFolder}/flix/imu.ino",
|
||||
"${workspaceFolder}/flix/led.ino",
|
||||
"${workspaceFolder}/flix/log.ino",
|
||||
"${workspaceFolder}/flix/mavlink.ino",
|
||||
"${workspaceFolder}/flix/motors.ino",
|
||||
"${workspaceFolder}/flix/rc.ino",
|
||||
"${workspaceFolder}/flix/time.ino",
|
||||
"${workspaceFolder}/flix/wifi.ino",
|
||||
"${workspaceFolder}/flix/parameters.ino"
|
||||
],
|
||||
"compilerPath": "~/Library/Arduino15/packages/esp32/tools/esp-x32/2411/bin/xtensa-esp32-elf-g++",
|
||||
"cStandard": "c11",
|
||||
@@ -87,7 +113,20 @@
|
||||
"forcedInclude": [
|
||||
"${workspaceFolder}/.vscode/intellisense.h",
|
||||
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32/Arduino.h",
|
||||
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32/pins_arduino.h"
|
||||
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32/pins_arduino.h",
|
||||
"${workspaceFolder}/flix/cli.ino",
|
||||
"${workspaceFolder}/flix/control.ino",
|
||||
"${workspaceFolder}/flix/estimate.ino",
|
||||
"${workspaceFolder}/flix/flix.ino",
|
||||
"${workspaceFolder}/flix/imu.ino",
|
||||
"${workspaceFolder}/flix/led.ino",
|
||||
"${workspaceFolder}/flix/log.ino",
|
||||
"${workspaceFolder}/flix/mavlink.ino",
|
||||
"${workspaceFolder}/flix/motors.ino",
|
||||
"${workspaceFolder}/flix/rc.ino",
|
||||
"${workspaceFolder}/flix/time.ino",
|
||||
"${workspaceFolder}/flix/wifi.ino",
|
||||
"${workspaceFolder}/flix/parameters.ino"
|
||||
],
|
||||
"compilerPath": "~/AppData/Local/Arduino15/packages/esp32/tools/esp-x32/2411/bin/xtensa-esp32-elf-g++.exe",
|
||||
"cStandard": "c11",
|
||||
|
||||
@@ -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.
|
||||
|
||||
@@ -3,8 +3,6 @@
|
||||
|
||||
// Implementation of command line interface
|
||||
|
||||
#include <Arduino.h>
|
||||
#include "flix.h"
|
||||
#include "pid.h"
|
||||
#include "vector.h"
|
||||
#include "util.h"
|
||||
@@ -13,6 +11,7 @@ extern const int MOTOR_REAR_LEFT, MOTOR_REAR_RIGHT, MOTOR_FRONT_RIGHT, MOTOR_FRO
|
||||
extern const int ACRO, STAB, AUTO;
|
||||
extern float t, dt, loopRate;
|
||||
extern uint16_t channels[16];
|
||||
extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlMode;
|
||||
extern int mode;
|
||||
extern bool armed;
|
||||
|
||||
@@ -71,13 +70,14 @@ void pause(float duration) {
|
||||
}
|
||||
}
|
||||
|
||||
void doCommand(String str, bool echo) {
|
||||
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) {
|
||||
attitude = Quaternion();
|
||||
} else if (command == "reboot") {
|
||||
ESP.restart();
|
||||
} else if (command == "") {
|
||||
// do nothing
|
||||
} else {
|
||||
print("Invalid command: %s\n", command.c_str());
|
||||
}
|
||||
@@ -1,55 +0,0 @@
|
||||
// Wi-Fi
|
||||
#define WIFI_ENABLED 1
|
||||
#define WIFI_SSID "flix"
|
||||
#define WIFI_PASSWORD "flixwifi"
|
||||
#define WIFI_UDP_PORT 14550
|
||||
#define WIFI_UDP_REMOTE_PORT 14550
|
||||
#define WIFI_UDP_REMOTE_ADDR "255.255.255.255"
|
||||
|
||||
// Motors
|
||||
#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
|
||||
|
||||
// Control
|
||||
#define PITCHRATE_P 0.05
|
||||
#define PITCHRATE_I 0.2
|
||||
#define PITCHRATE_D 0.001
|
||||
#define PITCHRATE_I_LIM 0.3
|
||||
#define ROLLRATE_P PITCHRATE_P
|
||||
#define ROLLRATE_I PITCHRATE_I
|
||||
#define ROLLRATE_D PITCHRATE_D
|
||||
#define ROLLRATE_I_LIM PITCHRATE_I_LIM
|
||||
#define YAWRATE_P 0.3
|
||||
#define YAWRATE_I 0.0
|
||||
#define YAWRATE_D 0.0
|
||||
#define YAWRATE_I_LIM 0.3
|
||||
#define ROLL_P 6
|
||||
#define ROLL_I 0
|
||||
#define ROLL_D 0
|
||||
#define PITCH_P ROLL_P
|
||||
#define PITCH_I ROLL_I
|
||||
#define PITCH_D ROLL_D
|
||||
#define YAW_P 3
|
||||
#define PITCHRATE_MAX radians(360)
|
||||
#define ROLLRATE_MAX radians(360)
|
||||
#define YAWRATE_MAX radians(300)
|
||||
#define TILT_MAX radians(30)
|
||||
#define RATES_D_LPF_ALPHA 0.2 // cutoff frequency ~ 40 Hz
|
||||
|
||||
// Estimation
|
||||
#define WEIGHT_ACC 0.003
|
||||
#define RATES_LFP_ALPHA 0.2 // cutoff frequency ~ 40 Hz
|
||||
|
||||
// MAVLink
|
||||
#define SYSTEM_ID 1
|
||||
|
||||
// Safety
|
||||
#define RC_LOSS_TIMEOUT 1
|
||||
#define DESCEND_TIME 10
|
||||
@@ -3,26 +3,40 @@
|
||||
|
||||
// Flight control
|
||||
|
||||
#include "config.h"
|
||||
#include "vector.h"
|
||||
#include "quaternion.h"
|
||||
#include "pid.h"
|
||||
#include "lpf.h"
|
||||
#include "util.h"
|
||||
|
||||
extern const int MANUAL = 0, ACRO = 1, STAB = 2, AUTO = 3; // flight modes
|
||||
extern const int MOTOR_REAR_LEFT, MOTOR_REAR_RIGHT, MOTOR_FRONT_RIGHT, MOTOR_FRONT_LEFT;
|
||||
#define PITCHRATE_P 0.05
|
||||
#define PITCHRATE_I 0.2
|
||||
#define PITCHRATE_D 0.001
|
||||
#define PITCHRATE_I_LIM 0.3
|
||||
#define ROLLRATE_P PITCHRATE_P
|
||||
#define ROLLRATE_I PITCHRATE_I
|
||||
#define ROLLRATE_D PITCHRATE_D
|
||||
#define ROLLRATE_I_LIM PITCHRATE_I_LIM
|
||||
#define YAWRATE_P 0.3
|
||||
#define YAWRATE_I 0.0
|
||||
#define YAWRATE_D 0.0
|
||||
#define YAWRATE_I_LIM 0.3
|
||||
#define ROLL_P 6
|
||||
#define ROLL_I 0
|
||||
#define ROLL_D 0
|
||||
#define PITCH_P ROLL_P
|
||||
#define PITCH_I ROLL_I
|
||||
#define PITCH_D ROLL_D
|
||||
#define YAW_P 3
|
||||
#define PITCHRATE_MAX radians(360)
|
||||
#define ROLLRATE_MAX radians(360)
|
||||
#define YAWRATE_MAX radians(300)
|
||||
#define TILT_MAX radians(30)
|
||||
#define RATES_D_LPF_ALPHA 0.2 // cutoff frequency ~ 40 Hz
|
||||
|
||||
const int MANUAL = 0, ACRO = 1, STAB = 2, AUTO = 3; // flight modes
|
||||
int mode = STAB;
|
||||
bool armed = false;
|
||||
float controlRoll, controlPitch, controlThrottle, controlYaw, controlMode;
|
||||
float controlTime;
|
||||
|
||||
Quaternion attitudeTarget;
|
||||
Vector ratesTarget;
|
||||
Vector ratesExtra; // feedforward rates
|
||||
Vector torqueTarget;
|
||||
float thrustTarget;
|
||||
|
||||
PID rollRatePID(ROLLRATE_P, ROLLRATE_I, ROLLRATE_D, ROLLRATE_I_LIM, RATES_D_LPF_ALPHA);
|
||||
PID pitchRatePID(PITCHRATE_P, PITCHRATE_I, PITCHRATE_D, PITCHRATE_I_LIM, RATES_D_LPF_ALPHA);
|
||||
@@ -33,6 +47,15 @@ PID yawPID(YAW_P, 0, 0);
|
||||
Vector maxRate(ROLLRATE_MAX, PITCHRATE_MAX, YAWRATE_MAX);
|
||||
float tiltMax = TILT_MAX;
|
||||
|
||||
Quaternion attitudeTarget;
|
||||
Vector ratesTarget;
|
||||
Vector ratesExtra; // feedforward rates
|
||||
Vector torqueTarget;
|
||||
float thrustTarget;
|
||||
|
||||
extern const int MOTOR_REAR_LEFT, MOTOR_REAR_RIGHT, MOTOR_FRONT_RIGHT, MOTOR_FRONT_LEFT;
|
||||
extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlMode;
|
||||
|
||||
void control() {
|
||||
interpretControls();
|
||||
failsafe();
|
||||
@@ -3,16 +3,13 @@
|
||||
|
||||
// Attitude estimation from gyro and accelerometer
|
||||
|
||||
#include "config.h"
|
||||
#include "flix.h"
|
||||
#include "quaternion.h"
|
||||
#include "vector.h"
|
||||
#include "lpf.h"
|
||||
#include "util.h"
|
||||
|
||||
Vector rates; // filtered angular rates, rad/s
|
||||
Quaternion attitude; // estimated attitude
|
||||
bool landed; // are we landed and stationary
|
||||
#define WEIGHT_ACC 0.003
|
||||
#define RATES_LFP_ALPHA 0.2 // cutoff frequency ~ 40 Hz
|
||||
|
||||
void estimate() {
|
||||
applyGyro();
|
||||
92
flix/flix.h
92
flix/flix.h
@@ -1,92 +0,0 @@
|
||||
// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
|
||||
// Repository: https://github.com/okalachev/flix
|
||||
|
||||
// All-in-one header file
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <Arduino.h>
|
||||
#include "vector.h"
|
||||
#include "quaternion.h"
|
||||
|
||||
// The most used global variables:
|
||||
extern float t; // current step time, s
|
||||
extern float dt; // time delta from previous step, s
|
||||
extern Vector gyro; // gyroscope data
|
||||
extern Vector acc; // accelerometer data, m/s²
|
||||
extern Vector rates; // filtered angular rates, rad/s
|
||||
extern Quaternion attitude; // estimated attitude
|
||||
extern float controlRoll, controlPitch, controlYaw, controlThrottle, controlMode; // pilot inputs, range [-1, 1]
|
||||
extern float controlTime; // inputs last update time
|
||||
extern int mode;
|
||||
extern bool armed;
|
||||
extern Vector ratesTarget, ratesExtra, torqueTarget;
|
||||
extern Quaternion attitudeTarget;
|
||||
extern float thrustTarget;
|
||||
extern bool landed; // are we landed and stationary
|
||||
extern float motors[4]; // normalized motors thrust in range [0..1]
|
||||
|
||||
void print(const char* format, ...);
|
||||
void pause(float duration);
|
||||
void doCommand(String str, bool echo = false);
|
||||
void handleInput();
|
||||
void control();
|
||||
void interpretControls();
|
||||
void controlAttitude();
|
||||
void controlRates();
|
||||
void controlTorque();
|
||||
const char *getModeName();
|
||||
void estimate();
|
||||
void applyGyro();
|
||||
void applyAcc();
|
||||
void setupIMU();
|
||||
void configureIMU();
|
||||
void readIMU();
|
||||
void rotateIMU(Vector& data);
|
||||
void calibrateGyroOnce();
|
||||
void calibrateAccel();
|
||||
void calibrateAccelOnce();
|
||||
void printIMUCalibration();
|
||||
void printIMUInfo();
|
||||
void setupLED();
|
||||
void setLED(bool on);
|
||||
void blinkLED();
|
||||
void prepareLogData();
|
||||
void logData();
|
||||
void dumpLog();
|
||||
void processMavlink();
|
||||
void sendMavlink();
|
||||
void sendMessage(const void *msg);
|
||||
void receiveMavlink();
|
||||
void handleMavlink(const void *_msg);
|
||||
void mavlinkPrint(const char* str);
|
||||
void sendMavlinkPrint();
|
||||
void setupMotors();
|
||||
int getDutyCycle(float value);
|
||||
void sendMotors();
|
||||
bool motorsActive();
|
||||
void testMotor(int n);
|
||||
void setupParameters();
|
||||
int parametersCount();
|
||||
const char *getParameterName(int index);
|
||||
float getParameter(int index);
|
||||
float getParameter(const char *name);
|
||||
bool setParameter(const char *name, const float value);
|
||||
void syncParameters();
|
||||
void printParameters();
|
||||
void resetParameters();
|
||||
void setupRC();
|
||||
bool readRC();
|
||||
void normalizeRC();
|
||||
void calibrateRC();
|
||||
void calibrateRCChannel(float *channel, uint16_t in[16], uint16_t out[16], const char *str);
|
||||
void printRCCalibration();
|
||||
void failsafe();
|
||||
void rcLossFailsafe();
|
||||
void descend();
|
||||
void autoFailsafe();
|
||||
void step();
|
||||
void computeLoopRate();
|
||||
void setupWiFi();
|
||||
void sendWiFi(const uint8_t *buf, int len);
|
||||
int receiveWiFi(uint8_t *buf, int len);
|
||||
@@ -3,14 +3,26 @@
|
||||
|
||||
// Main firmware file
|
||||
|
||||
#include "config.h"
|
||||
#include "vector.h"
|
||||
#include "quaternion.h"
|
||||
#include "util.h"
|
||||
#include "flix.h"
|
||||
|
||||
#define SERIAL_BAUDRATE 115200
|
||||
#define WIFI_ENABLED 1
|
||||
|
||||
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;
|
||||
Vector gyro; // gyroscope data
|
||||
Vector acc; // accelerometer data, m/s/s
|
||||
Vector rates; // filtered angular rates, rad/s
|
||||
Quaternion attitude; // estimated attitude
|
||||
bool landed; // are we landed and stationary
|
||||
float motors[4]; // normalized motors thrust in range [0..1]
|
||||
|
||||
void setup() {
|
||||
Serial.begin(115200);
|
||||
Serial.begin(SERIAL_BAUDRATE);
|
||||
print("Initializing flix\n");
|
||||
disableBrownOut();
|
||||
setupParameters();
|
||||
|
||||
@@ -11,10 +11,9 @@
|
||||
|
||||
MPU9250 imu(SPI);
|
||||
|
||||
Vector gyro, gyroBias;
|
||||
Vector acc, accBias, accScale(1, 1, 1);
|
||||
|
||||
extern float loopRate;
|
||||
Vector accBias;
|
||||
Vector accScale(1, 1, 1);
|
||||
Vector gyroBias;
|
||||
|
||||
void setupIMU() {
|
||||
print("Setup IMU\n");
|
||||
@@ -3,8 +3,6 @@
|
||||
|
||||
// Board's LED control
|
||||
|
||||
#include <Arduino.h>
|
||||
|
||||
#define BLINK_PERIOD 500000
|
||||
|
||||
#ifndef LED_BUILTIN
|
||||
@@ -3,7 +3,6 @@
|
||||
|
||||
// In-RAM logging
|
||||
|
||||
#include "flix.h"
|
||||
#include "vector.h"
|
||||
|
||||
#define LOG_RATE 100
|
||||
@@ -5,8 +5,6 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <Arduino.h>
|
||||
|
||||
template <typename T> // Using template to make the filter usable for scalar and vector values
|
||||
class LowPassFilter {
|
||||
public:
|
||||
|
||||
@@ -3,24 +3,20 @@
|
||||
|
||||
// MAVLink communication
|
||||
|
||||
#include <Arduino.h>
|
||||
#include "config.h"
|
||||
#include "flix.h"
|
||||
|
||||
#if WIFI_ENABLED
|
||||
|
||||
#include <MAVLink.h>
|
||||
|
||||
#define SYSTEM_ID 1
|
||||
#define PERIOD_SLOW 1.0
|
||||
#define PERIOD_FAST 0.1
|
||||
#define MAVLINK_CONTROL_YAW_DEAD_ZONE 0.1f
|
||||
|
||||
bool mavlinkConnected = false;
|
||||
String mavlinkPrintBuffer;
|
||||
|
||||
extern uint16_t channels[16];
|
||||
extern float controlTime;
|
||||
extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlMode;
|
||||
extern const int STAB, AUTO;
|
||||
|
||||
void processMavlink() {
|
||||
sendMavlink();
|
||||
@@ -46,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};
|
||||
@@ -85,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;
|
||||
@@ -4,43 +4,53 @@
|
||||
// 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)
|
||||
|
||||
#include <Arduino.h>
|
||||
#include "config.h"
|
||||
#include "flix.h"
|
||||
#include "util.h"
|
||||
|
||||
float motors[4]; // normalized motors thrust in range [0..1]
|
||||
extern const int MOTOR_REAR_LEFT = 0;
|
||||
extern const int MOTOR_REAR_RIGHT = 1;
|
||||
extern const int MOTOR_FRONT_RIGHT = 2;
|
||||
extern const int MOTOR_FRONT_LEFT = 3;
|
||||
#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
|
||||
|
||||
// Motors array indexes:
|
||||
const int MOTOR_REAR_LEFT = 0;
|
||||
const int MOTOR_REAR_RIGHT = 1;
|
||||
const int MOTOR_FRONT_RIGHT = 2;
|
||||
const int MOTOR_FRONT_LEFT = 3;
|
||||
|
||||
void setupMotors() {
|
||||
print("Setup Motors\n");
|
||||
|
||||
// configure pins
|
||||
#ifdef ESP32
|
||||
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);
|
||||
|
||||
#else
|
||||
analogWriteResolution(PWM_RESOLUTION);
|
||||
analogWriteFrequency(PWM_FREQUENCY);
|
||||
#endif
|
||||
sendMotors();
|
||||
print("Motors initialized\n");
|
||||
}
|
||||
|
||||
int getDutyCycle(float value) {
|
||||
value = constrain(value, 0, 1);
|
||||
float pwm = mapff(value, 0, 1, PWM_MIN, PWM_MAX);
|
||||
float pwm = mapf(value, 0, 1, PWM_MIN, PWM_MAX);
|
||||
if (value == 0) pwm = PWM_STOP;
|
||||
float duty = mapff(pwm, 0, 1000000 / PWM_FREQUENCY, 0, (1 << PWM_RESOLUTION) - 1);
|
||||
float duty = mapf(pwm, 0, 1000000 / PWM_FREQUENCY, 0, (1 << PWM_RESOLUTION) - 1);
|
||||
return round(duty);
|
||||
}
|
||||
|
||||
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]));
|
||||
analogWrite(MOTOR_0_PIN, getDutyCycle(motors[0]));
|
||||
analogWrite(MOTOR_1_PIN, getDutyCycle(motors[1]));
|
||||
analogWrite(MOTOR_2_PIN, getDutyCycle(motors[2]));
|
||||
analogWrite(MOTOR_3_PIN, getDutyCycle(motors[3]));
|
||||
}
|
||||
|
||||
bool motorsActive() {
|
||||
@@ -4,17 +4,10 @@
|
||||
// Parameters storage in flash memory
|
||||
|
||||
#include <Preferences.h>
|
||||
#include "flix.h"
|
||||
#include "pid.h"
|
||||
|
||||
extern float channelZero[16];
|
||||
extern float channelMax[16];
|
||||
extern float rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel;
|
||||
extern float tiltMax;
|
||||
extern PID rollPID, pitchPID, yawPID;
|
||||
extern PID rollRatePID, pitchRatePID, yawRatePID;
|
||||
extern Vector maxRate;
|
||||
extern Vector accBias, accScale;
|
||||
|
||||
Preferences storage;
|
||||
|
||||
@@ -5,8 +5,6 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "Arduino.h"
|
||||
#include "flix.h"
|
||||
#include "lpf.h"
|
||||
|
||||
class PID {
|
||||
|
||||
@@ -5,7 +5,6 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <Arduino.h>
|
||||
#include "vector.h"
|
||||
|
||||
class Quaternion : public Printable {
|
||||
|
||||
@@ -9,6 +9,7 @@
|
||||
SBUS rc(Serial2); // NOTE: Use RC(Serial2, 16, 17) if you use the old UART2 pins
|
||||
|
||||
uint16_t channels[16]; // raw rc channels
|
||||
float controlTime; // time of the last controls update
|
||||
float channelZero[16]; // calibration zero values
|
||||
float channelMax[16]; // calibration max values
|
||||
|
||||
@@ -3,11 +3,11 @@
|
||||
|
||||
// Fail-safe functions
|
||||
|
||||
#include "config.h"
|
||||
#include "flix.h"
|
||||
#define RC_LOSS_TIMEOUT 1
|
||||
#define DESCEND_TIME 10
|
||||
|
||||
extern float controlTime;
|
||||
extern const int AUTO, STAB;
|
||||
extern float controlRoll, controlPitch, controlThrottle, controlYaw;
|
||||
|
||||
void failsafe() {
|
||||
rcLossFailsafe();
|
||||
@@ -3,11 +3,6 @@
|
||||
|
||||
// Time related functions
|
||||
|
||||
#include "Arduino.h"
|
||||
#include "flix.h"
|
||||
|
||||
float t = NAN; // current step time, s
|
||||
float dt; // time delta from previous step, s
|
||||
float loopRate; // Hz
|
||||
|
||||
void step() {
|
||||
22
flix/util.h
22
flix/util.h
@@ -6,30 +6,28 @@
|
||||
#pragma once
|
||||
|
||||
#include <math.h>
|
||||
#ifdef ESP32
|
||||
#include <soc/soc.h>
|
||||
#include <soc/rtc_cntl_reg.h>
|
||||
#include "flix.h"
|
||||
#endif
|
||||
|
||||
const float ONE_G = 9.80665;
|
||||
extern float t;
|
||||
|
||||
inline 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;
|
||||
}
|
||||
|
||||
inline float mapff(float x, float in_min, float in_max, float out_min, float out_max) {
|
||||
float mapf(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;
|
||||
}
|
||||
|
||||
inline bool invalid(float x) {
|
||||
bool invalid(float x) {
|
||||
return !isfinite(x);
|
||||
}
|
||||
|
||||
inline bool valid(float x) {
|
||||
bool valid(float x) {
|
||||
return isfinite(x);
|
||||
}
|
||||
|
||||
// Wrap angle to [-PI, PI)
|
||||
inline float wrapAngle(float angle) {
|
||||
float wrapAngle(float angle) {
|
||||
angle = fmodf(angle, 2 * PI);
|
||||
if (angle > PI) {
|
||||
angle -= 2 * PI;
|
||||
@@ -40,12 +38,14 @@ inline float wrapAngle(float angle) {
|
||||
}
|
||||
|
||||
// Disable reset on low voltage
|
||||
inline void disableBrownOut() {
|
||||
void disableBrownOut() {
|
||||
#ifdef ESP32
|
||||
REG_CLR_BIT(RTC_CNTL_BROWN_OUT_REG, RTC_CNTL_BROWN_OUT_ENA);
|
||||
#endif
|
||||
}
|
||||
|
||||
// Trim and split string by spaces
|
||||
inline void splitString(String& str, String& token0, String& token1, String& token2) {
|
||||
void splitString(String& str, String& token0, String& token1, String& token2) {
|
||||
str.trim();
|
||||
char chars[str.length() + 1];
|
||||
str.toCharArray(chars, str.length() + 1);
|
||||
|
||||
@@ -5,8 +5,6 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <Arduino.h>
|
||||
|
||||
class Vector : public Printable {
|
||||
public:
|
||||
float x, y, z;
|
||||
@@ -126,5 +124,5 @@ public:
|
||||
}
|
||||
};
|
||||
|
||||
inline Vector operator * (const float a, const Vector& b) { return b * a; }
|
||||
inline Vector operator + (const float a, const Vector& b) { return b + a; }
|
||||
Vector operator * (const float a, const Vector& b) { return b * a; }
|
||||
Vector operator + (const float a, const Vector& b) { return b + a; }
|
||||
|
||||
@@ -3,15 +3,18 @@
|
||||
|
||||
// Wi-Fi support
|
||||
|
||||
#include "config.h"
|
||||
#include "flix.h"
|
||||
|
||||
#if WIFI_ENABLED
|
||||
|
||||
#include <WiFi.h>
|
||||
#include <WiFiAP.h>
|
||||
#include <WiFiUdp.h>
|
||||
|
||||
#define WIFI_SSID "flix"
|
||||
#define WIFI_PASSWORD "flixwifi"
|
||||
#define WIFI_UDP_PORT 14550
|
||||
#define WIFI_UDP_REMOTE_PORT 14550
|
||||
#define WIFI_UDP_REMOTE_ADDR "255.255.255.255"
|
||||
|
||||
WiFiUDP udp;
|
||||
|
||||
void setupWiFi() {
|
||||
Reference in New Issue
Block a user