Files
flix/flix/parameters.ino
Oleg Kalachev 3e49d41986 Make rc channel numbers and calibration params use int instead of float
As parameter subsystems supports int now, and int is much more natural here.
2026-02-02 20:36:22 +03:00

186 lines
5.5 KiB
C++

// Copyright (c) 2024 Oleg Kalachev <okalachev@gmail.com>
// Repository: https://github.com/okalachev/flix
// Parameters storage in flash memory
#include <Preferences.h>
#include "util.h"
extern int channelZero[16];
extern int channelMax[16];
extern int rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel;
extern int wifiMode, udpLocalPort, udpRemotePort;
extern float rcLossTimeout, descendTime;
Preferences storage;
struct Parameter {
const char *name; // max length is 15
bool integer;
union { float *f; int *i; }; // pointer to the variable
float cache; // what's stored in flash
Parameter(const char *name, float *variable) : name(name), integer(false), f(variable) {};
Parameter(const char *name, int *variable) : name(name), integer(true), i(variable) {};
float getValue() const { return integer ? *i : *f; };
void setValue(const float value) { if (integer) *i = value; else *f = value; };
};
Parameter parameters[] = {
// control
{"CTL_R_RATE_P", &rollRatePID.p},
{"CTL_R_RATE_I", &rollRatePID.i},
{"CTL_R_RATE_D", &rollRatePID.d},
{"CTL_R_RATE_WU", &rollRatePID.windup},
{"CTL_P_RATE_P", &pitchRatePID.p},
{"CTL_P_RATE_I", &pitchRatePID.i},
{"CTL_P_RATE_D", &pitchRatePID.d},
{"CTL_P_RATE_WU", &pitchRatePID.windup},
{"CTL_Y_RATE_P", &yawRatePID.p},
{"CTL_Y_RATE_I", &yawRatePID.i},
{"CTL_Y_RATE_D", &yawRatePID.d},
{"CTL_R_P", &rollPID.p},
{"CTL_R_I", &rollPID.i},
{"CTL_R_D", &rollPID.d},
{"CTL_P_P", &pitchPID.p},
{"CTL_P_I", &pitchPID.i},
{"CTL_P_D", &pitchPID.d},
{"CTL_Y_P", &yawPID.p},
{"CTL_P_RATE_MAX", &maxRate.y},
{"CTL_R_RATE_MAX", &maxRate.x},
{"CTL_Y_RATE_MAX", &maxRate.z},
{"CTL_TILT_MAX", &tiltMax},
{"CTL_FLT_MODE_0", &flightModes[0]},
{"CTL_FLT_MODE_1", &flightModes[1]},
{"CTL_FLT_MODE_2", &flightModes[2]},
// imu
{"IMU_ROT_ROLL", &imuRotation.x},
{"IMU_ROT_PITCH", &imuRotation.y},
{"IMU_ROT_YAW", &imuRotation.z},
{"IMU_ACC_BIAS_X", &accBias.x},
{"IMU_ACC_BIAS_Y", &accBias.y},
{"IMU_ACC_BIAS_Z", &accBias.z},
{"IMU_ACC_SCALE_X", &accScale.x},
{"IMU_ACC_SCALE_Y", &accScale.y},
{"IMU_ACC_SCALE_Z", &accScale.z},
{"IMU_GYRO_BIAS_A", &gyroBiasFilter.alpha},
// estimate
{"EST_ACC_WEIGHT", &accWeight},
{"EST_RATES_LPF_A", &ratesFilter.alpha},
// motors
{"MOT_PIN_FL", &motorPins[MOTOR_FRONT_LEFT]},
{"MOT_PIN_FR", &motorPins[MOTOR_FRONT_RIGHT]},
{"MOT_PIN_RL", &motorPins[MOTOR_REAR_LEFT]},
{"MOT_PIN_RR", &motorPins[MOTOR_REAR_RIGHT]},
{"MOT_PWM_FREQ", &pwmFrequency},
{"MOT_PWM_RES", &pwmResolution},
{"MOT_PWM_STOP", &pwmStop},
{"MOT_PWM_MIN", &pwmMin},
{"MOT_PWM_MAX", &pwmMax},
// rc
{"RC_ZERO_0", &channelZero[0]},
{"RC_ZERO_1", &channelZero[1]},
{"RC_ZERO_2", &channelZero[2]},
{"RC_ZERO_3", &channelZero[3]},
{"RC_ZERO_4", &channelZero[4]},
{"RC_ZERO_5", &channelZero[5]},
{"RC_ZERO_6", &channelZero[6]},
{"RC_ZERO_7", &channelZero[7]},
{"RC_MAX_0", &channelMax[0]},
{"RC_MAX_1", &channelMax[1]},
{"RC_MAX_2", &channelMax[2]},
{"RC_MAX_3", &channelMax[3]},
{"RC_MAX_4", &channelMax[4]},
{"RC_MAX_5", &channelMax[5]},
{"RC_MAX_6", &channelMax[6]},
{"RC_MAX_7", &channelMax[7]},
{"RC_ROLL", &rollChannel},
{"RC_PITCH", &pitchChannel},
{"RC_THROTTLE", &throttleChannel},
{"RC_YAW", &yawChannel},
{"RC_MODE", &modeChannel},
// wifi
{"WIFI_MODE", &wifiMode},
{"WIFI_LOC_PORT", &udpLocalPort},
{"WIFI_REM_PORT", &udpRemotePort},
// mavlink
{"MAV_SYS_ID", &mavlinkSysId},
{"MAV_RATE_SLOW", &telemetrySlow.rate},
{"MAV_RATE_FAST", &telemetryFast.rate},
// safety
{"SF_RC_LOSS_TIME", &rcLossTimeout},
{"SF_DESCEND_TIME", &descendTime},
};
void setupParameters() {
print("Setup parameters\n");
storage.begin("flix", false);
// Read parameters from storage
for (auto &parameter : parameters) {
if (!storage.isKey(parameter.name)) {
storage.putFloat(parameter.name, parameter.getValue()); // store default value
}
parameter.setValue(storage.getFloat(parameter.name, 0));
parameter.cache = parameter.getValue();
}
}
int parametersCount() {
return sizeof(parameters) / sizeof(parameters[0]);
}
const char *getParameterName(int index) {
if (index < 0 || index >= parametersCount()) return "";
return parameters[index].name;
}
float getParameter(int index) {
if (index < 0 || index >= parametersCount()) return NAN;
return parameters[index].getValue();
}
float getParameter(const char *name) {
for (auto &parameter : parameters) {
if (strcasecmp(parameter.name, name) == 0) {
return parameter.getValue();
}
}
return NAN;
}
bool setParameter(const char *name, const float value) {
for (auto &parameter : parameters) {
if (strcasecmp(parameter.name, name) == 0) {
if (parameter.integer && !isfinite(value)) return false; // can't set integer to NaN or Inf
parameter.setValue(value);
return true;
}
}
return false;
}
void syncParameters() {
static Rate rate(1);
if (!rate) return; // sync once per second
if (motorsActive()) return; // don't use flash while flying, it may cause a delay
for (auto &parameter : parameters) {
if (parameter.getValue() == parameter.cache) continue; // no change
if (isnan(parameter.getValue()) && isnan(parameter.cache)) continue; // both are NaN
if (isinf(parameter.getValue()) && isinf(parameter.cache)) continue; // both are Inf
storage.putFloat(parameter.name, parameter.getValue());
parameter.cache = parameter.getValue(); // update cache
}
}
void printParameters() {
for (auto &parameter : parameters) {
print("%s = %g\n", parameter.name, parameter.getValue());
}
}
void resetParameters() {
storage.clear();
ESP.restart();
}