// Copyright (c) 2024 Oleg Kalachev // Repository: https://github.com/okalachev/flix // Parameters storage in flash memory #include #include "util.h" extern float channelZero[16]; extern float channelMax[16]; extern float rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel; Preferences storage; struct Parameter { const char *name; // max length is 15 (Preferences key limit) float *variable; float value; // cache }; 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}, // 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}, // estimate {"EST_ACC_WEIGHT", &accWeight}, {"EST_RATES_LPF_A", &ratesFilter.alpha}, // 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}, }; void setupParameters() { storage.begin("flix", false); // Read parameters from storage for (auto ¶meter : parameters) { if (!storage.isKey(parameter.name)) { storage.putFloat(parameter.name, *parameter.variable); } *parameter.variable = storage.getFloat(parameter.name, *parameter.variable); parameter.value = *parameter.variable; } } 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].variable; } float getParameter(const char *name) { for (auto ¶meter : parameters) { if (strcmp(parameter.name, name) == 0) { return *parameter.variable; } } return NAN; } bool setParameter(const char *name, const float value) { for (auto ¶meter : parameters) { if (strcmp(parameter.name, name) == 0) { *parameter.variable = 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 ¶meter : parameters) { if (parameter.value == *parameter.variable) continue; if (isnan(parameter.value) && isnan(*parameter.variable)) continue; // handle NAN != NAN storage.putFloat(parameter.name, *parameter.variable); parameter.value = *parameter.variable; } } void printParameters() { for (auto ¶meter : parameters) { print("%s = %g\n", parameter.name, *parameter.variable); } } void resetParameters() { storage.clear(); ESP.restart(); }