Several minor changes

This commit is contained in:
Oleg Kalachev
2026-02-02 18:46:36 +03:00
parent 3631743a29
commit 67430c7aac
4 changed files with 10 additions and 8 deletions

View File

@@ -1,7 +1,7 @@
// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com> // Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
// Repository: https://github.com/okalachev/flix // Repository: https://github.com/okalachev/flix
// Attitude estimation from gyro and accelerometer // Attitude estimation using gyro and accelerometer
#include "quaternion.h" #include "quaternion.h"
#include "vector.h" #include "vector.h"

View File

@@ -21,8 +21,8 @@ void setup() {
disableBrownOut(); disableBrownOut();
setupParameters(); setupParameters();
setupLED(); setupLED();
setupMotors();
setLED(true); setLED(true);
setupMotors();
setupWiFi(); setupWiFi();
setupIMU(); setupIMU();
setupRC(); setupRC();

View File

@@ -8,12 +8,13 @@
extern float controlTime; extern float controlTime;
bool mavlinkConnected = false;
String mavlinkPrintBuffer;
int mavlinkSysId = 1; int mavlinkSysId = 1;
Rate telemetryFast(10); Rate telemetryFast(10);
Rate telemetrySlow(2); Rate telemetrySlow(2);
bool mavlinkConnected = false;
String mavlinkPrintBuffer;
void processMavlink() { void processMavlink() {
sendMavlink(); sendMavlink();
receiveMavlink(); receiveMavlink();
@@ -41,9 +42,9 @@ void sendMavlink() {
} }
if (telemetryFast && mavlinkConnected) { if (telemetryFast && mavlinkConnected) {
const float zeroQuat[] = {0, 0, 0, 0}; const float offset[] = {0, 0, 0, 0};
mavlink_msg_attitude_quaternion_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg, mavlink_msg_attitude_quaternion_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg,
time, attitude.w, attitude.x, -attitude.y, -attitude.z, rates.x, -rates.y, -rates.z, zeroQuat); // convert to frd time, attitude.w, attitude.x, -attitude.y, -attitude.z, rates.x, -rates.y, -rates.z, offset); // convert to frd
sendMessage(&msg); sendMessage(&msg);
mavlink_msg_rc_channels_raw_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg, controlTime * 1000, 0, mavlink_msg_rc_channels_raw_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg, controlTime * 1000, 0,

View File

@@ -15,9 +15,9 @@ extern float rcLossTimeout, descendTime;
Preferences storage; Preferences storage;
struct Parameter { struct Parameter {
const char *name; // max length is 15 (Preferences key limit) const char *name; // max length is 15
bool integer; bool integer;
union { float *f; int *i; }; // pointer to variable union { float *f; int *i; }; // pointer to the variable
float cache; // what's stored in flash float cache; // what's stored in flash
Parameter(const char *name, float *variable) : name(name), integer(false), f(variable) {}; Parameter(const char *name, float *variable) : name(name), integer(false), f(variable) {};
Parameter(const char *name, int *variable) : name(name), integer(true), i(variable) {}; Parameter(const char *name, int *variable) : name(name), integer(true), i(variable) {};
@@ -112,6 +112,7 @@ Parameter parameters[] = {
}; };
void setupParameters() { void setupParameters() {
print("Setup parameters\n");
storage.begin("flix", false); storage.begin("flix", false);
// Read parameters from storage // Read parameters from storage
for (auto &parameter : parameters) { for (auto &parameter : parameters) {