8 Commits
master ... cpp

Author SHA1 Message Date
Oleg Kalachev
385226bc97 Add sources to the simulator using cmake instead of include 2026-01-09 17:01:14 +03:00
Oleg Kalachev
e7e57d1020 Fix 2026-01-09 09:46:56 +03:00
Oleg Kalachev
213b9788a9 Fixes 2026-01-09 09:45:23 +03:00
Oleg Kalachev
69fb5d30f6 Merge branch 'master' into cpp 2026-01-09 09:41:31 +03:00
Oleg Kalachev
e59a190c1c Fix 2025-10-21 18:41:58 +03:00
Oleg Kalachev
207c0e41f7 Add parameters to config.h 2025-10-21 18:38:51 +03:00
Oleg Kalachev
d7d79ff03f Make .cpp style version compile 2025-10-21 18:31:54 +03:00
Oleg Kalachev
6725f1d3de Change source files type from ino to cpp 2025-10-20 23:06:13 +03:00
24 changed files with 235 additions and 130 deletions

View File

@@ -18,20 +18,7 @@
"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",
"${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"
"~/.arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32/pins_arduino.h"
],
"compilerPath": "~/.arduino15/packages/esp32/tools/esp-x32/2411/bin/xtensa-esp32-elf-g++",
"cStandard": "c11",
@@ -65,20 +52,7 @@
"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",
"${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"
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32/pins_arduino.h"
],
"compilerPath": "~/Library/Arduino15/packages/esp32/tools/esp-x32/2411/bin/xtensa-esp32-elf-g++",
"cStandard": "c11",
@@ -113,20 +87,7 @@
"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",
"${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"
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32/pins_arduino.h"
],
"compilerPath": "~/AppData/Local/Arduino15/packages/esp32/tools/esp-x32/2411/bin/xtensa-esp32-elf-g++.exe",
"cStandard": "c11",

View File

@@ -3,6 +3,8 @@
// Implementation of command line interface
#include <Arduino.h>
#include "flix.h"
#include "pid.h"
#include "vector.h"
#include "util.h"
@@ -71,7 +73,7 @@ void pause(float duration) {
}
}
void doCommand(String str, bool echo = false) {
void doCommand(String str, bool echo) {
// parse command
String command, arg0, arg1;
splitString(str, command, arg0, arg1);

55
flix/config.h Normal file
View File

@@ -0,0 +1,55 @@
// 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

View File

@@ -3,41 +3,25 @@
// Flight control
#include "config.h"
#include "flix.h"
#include "vector.h"
#include "quaternion.h"
#include "pid.h"
#include "lpf.h"
#include "util.h"
#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
extern const int RAW = 0, ACRO = 1, STAB = 2, AUTO = 3; // flight modes
const int RAW = 0, ACRO = 1, STAB = 2, AUTO = 3; // flight modes
int mode = STAB;
bool armed = false;
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);
PID yawRatePID(YAWRATE_P, YAWRATE_I, YAWRATE_D);
@@ -47,12 +31,6 @@ 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;

View File

@@ -3,6 +3,8 @@
// Attitude estimation from gyro and accelerometer
#include "config.h"
#include "flix.h"
#include "quaternion.h"
#include "vector.h"
#include "lpf.h"

90
flix/flix.h Normal file
View File

@@ -0,0 +1,90 @@
// 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"
extern float t, dt;
extern float loopRate;
extern float controlRoll, controlPitch, controlYaw, controlThrottle, controlMode;
extern Vector gyro, acc;
extern Vector rates;
extern Quaternion attitude;
extern bool landed;
extern int mode;
extern bool armed;
extern Quaternion attitudeTarget;
extern Vector ratesTarget, ratesExtra, torqueTarget;
extern float thrustTarget;
extern float motors[4];
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 printLogHeader();
void printLogData();
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);

View File

@@ -3,19 +3,11 @@
// Main firmware file
#include "config.h"
#include "vector.h"
#include "quaternion.h"
#include "util.h"
#define WIFI_ENABLED 1
extern float t, dt;
extern float controlRoll, controlPitch, controlYaw, controlThrottle, controlMode;
extern Vector gyro, acc;
extern Vector rates;
extern Quaternion attitude;
extern bool landed;
extern float motors[4];
#include "flix.h"
void setup() {
Serial.begin(115200);

View File

@@ -3,6 +3,8 @@
// Board's LED control
#include <Arduino.h>
#define BLINK_PERIOD 500000
#ifndef LED_BUILTIN

View File

@@ -3,6 +3,7 @@
// In-RAM logging
#include "flix.h"
#include "vector.h"
#include "util.h"

View File

@@ -5,6 +5,8 @@
#pragma once
#include <Arduino.h>
template <typename T> // Using template to make the filter usable for scalar and vector values
class LowPassFilter {
public:

View File

@@ -3,6 +3,10 @@
// MAVLink communication
#include <Arduino.h>
#include "config.h"
#include "flix.h"
#if WIFI_ENABLED
#include <MAVLink.h>
@@ -12,6 +16,8 @@
#define MAVLINK_RATE_SLOW 1
#define MAVLINK_RATE_FAST 10
extern const int AUTO, STAB;
extern uint16_t channels[16];
extern float controlTime;
bool mavlinkConnected = false;
@@ -206,6 +212,7 @@ void handleMavlink(const void *_msg) {
armed = motors[0] > 0 || motors[1] > 0 || motors[2] > 0 || motors[3] > 0;
}
/* TODO:
if (msg.msgid == MAVLINK_MSG_ID_LOG_REQUEST_DATA) {
mavlink_log_request_data_t m;
mavlink_msg_log_request_data_decode(&msg, &m);
@@ -219,6 +226,7 @@ void handleMavlink(const void *_msg) {
sendMessage(&msg);
}
}
*/
// Handle commands
if (msg.msgid == MAVLINK_MSG_ID_COMMAND_LONG) {

View File

@@ -4,25 +4,17 @@
// 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"
#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
float motors[4]; // normalized motor thrusts in range [0..1]
const int MOTOR_REAR_LEFT = 0;
const int MOTOR_REAR_RIGHT = 1;
const int MOTOR_FRONT_RIGHT = 2;
const int MOTOR_FRONT_LEFT = 3;
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;
void setupMotors() {
print("Setup Motors\n");

View File

@@ -4,11 +4,22 @@
// Parameters storage in flash memory
#include <Preferences.h>
#include "flix.h"
#include "pid.h"
#include "lpf.h"
#include "util.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 imuRotation;
extern Vector accBias, accScale;
extern float accWeight;
extern LowPassFilter<Vector> ratesFilter;
Preferences storage;

View File

@@ -5,6 +5,8 @@
#pragma once
#include "Arduino.h"
#include "flix.h"
#include "lpf.h"
class PID {

View File

@@ -5,6 +5,7 @@
#pragma once
#include <Arduino.h>
#include "vector.h"
class Quaternion : public Printable {

View File

@@ -3,11 +3,11 @@
// Fail-safe functions
#define RC_LOSS_TIMEOUT 1
#define DESCEND_TIME 10
#include "config.h"
#include "flix.h"
extern float controlTime;
extern float controlRoll, controlPitch, controlThrottle, controlYaw;
extern const int AUTO, STAB;
void failsafe() {
rcLossFailsafe();

View File

@@ -3,6 +3,9 @@
// Time related functions
#include "Arduino.h"
#include "flix.h"
float t = NAN; // current time, s
float dt; // time delta with the previous step, s
float loopRate; // Hz

View File

@@ -8,24 +8,24 @@
#include <math.h>
#include <soc/soc.h>
#include <soc/rtc_cntl_reg.h>
#include "flix.h"
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) {
inline 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;
}
bool invalid(float x) {
inline bool invalid(float x) {
return !isfinite(x);
}
bool valid(float x) {
inline bool valid(float x) {
return isfinite(x);
}
// Wrap angle to [-PI, PI)
float wrapAngle(float angle) {
inline float wrapAngle(float angle) {
angle = fmodf(angle, 2 * PI);
if (angle > PI) {
angle -= 2 * PI;
@@ -36,12 +36,12 @@ float wrapAngle(float angle) {
}
// Disable reset on low voltage
void disableBrownOut() {
inline void disableBrownOut() {
REG_CLR_BIT(RTC_CNTL_BROWN_OUT_REG, RTC_CNTL_BROWN_OUT_ENA);
}
// Trim and split string by spaces
void splitString(String& str, String& token0, String& token1, String& token2) {
inline void splitString(String& str, String& token0, String& token1, String& token2) {
str.trim();
char chars[str.length() + 1];
str.toCharArray(chars, str.length() + 1);

View File

@@ -5,6 +5,8 @@
#pragma once
#include <Arduino.h>
class Vector : public Printable {
public:
float x, y, z;
@@ -123,5 +125,5 @@ public:
}
};
Vector operator * (const float a, const Vector& b) { return b * a; }
Vector operator + (const float a, const Vector& b) { return b + a; }
inline Vector operator * (const float a, const Vector& b) { return b * a; }
inline Vector operator + (const float a, const Vector& b) { return b + a; }

View File

@@ -3,20 +3,19 @@
// 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;
extern bool mavlinkConnected;
void setupWiFi() {
print("Setup Wi-Fi\n");
WiFi.softAP(WIFI_SSID, WIFI_PASSWORD);

View File

@@ -10,9 +10,23 @@ list(APPEND CMAKE_CXX_FLAGS "${GAZEBO_CXX_FLAGS}")
set(FLIX_SOURCE_DIR ../flix)
include_directories(${FLIX_SOURCE_DIR})
set(FLIX_SOURCE_DIR ../flix)
include_directories(${FLIX_SOURCE_DIR})
set(FLIX_SOURCES
${FLIX_SOURCE_DIR}/cli.cpp
${FLIX_SOURCE_DIR}/control.cpp
${FLIX_SOURCE_DIR}/estimate.cpp
${FLIX_SOURCE_DIR}/safety.cpp
${FLIX_SOURCE_DIR}/log.cpp
${FLIX_SOURCE_DIR}/mavlink.cpp
${FLIX_SOURCE_DIR}/motors.cpp
${FLIX_SOURCE_DIR}/parameters.cpp
${FLIX_SOURCE_DIR}/rc.cpp
${FLIX_SOURCE_DIR}/time.cpp
)
set(CMAKE_BUILD_TYPE RelWithDebInfo)
add_library(flix SHARED simulator.cpp)
add_library(flix SHARED simulator.cpp ${FLIX_SOURCES})
target_link_libraries(flix ${GAZEBO_LIBRARIES} ${SDL2_LIBRARIES})
target_include_directories(flix PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})
target_compile_options(flix PRIVATE -Wno-address-of-packed-member) # disable unneeded mavlink warnings

View File

@@ -18,18 +18,6 @@
#include "Arduino.h"
#include "flix.h"
#include "cli.ino"
#include "control.ino"
#include "estimate.ino"
#include "safety.ino"
#include "log.ino"
#include "lpf.h"
#include "mavlink.ino"
#include "motors.ino"
#include "parameters.ino"
#include "rc.ino"
#include "time.ino"
using ignition::math::Vector3d;
using namespace gazebo;
using namespace std;