Added battery cell count based automatic PID profile switching.
This commit is contained in:
parent
90e50c9f48
commit
299d96fdc7
|
@ -3329,7 +3329,7 @@ static void cliProfile(char *cmdline)
|
|||
return;
|
||||
} else {
|
||||
const int i = atoi(cmdline);
|
||||
if (i >= 0 && i < MAX_PROFILE_COUNT) {
|
||||
if (i >= 0 && i < PID_PROFILE_COUNT) {
|
||||
changePidProfile(i);
|
||||
cliProfile("");
|
||||
}
|
||||
|
@ -3352,7 +3352,7 @@ static void cliRateProfile(char *cmdline)
|
|||
|
||||
static void cliDumpPidProfile(uint8_t pidProfileIndex, uint8_t dumpMask)
|
||||
{
|
||||
if (pidProfileIndex >= MAX_PROFILE_COUNT) {
|
||||
if (pidProfileIndex >= PID_PROFILE_COUNT) {
|
||||
// Faulty values
|
||||
return;
|
||||
}
|
||||
|
@ -4764,7 +4764,7 @@ static void printConfig(char *cmdline, bool doDiff)
|
|||
dumpAllValues(MASTER_VALUE, dumpMask);
|
||||
|
||||
if (dumpMask & DUMP_ALL) {
|
||||
for (uint32_t pidProfileIndex = 0; pidProfileIndex < MAX_PROFILE_COUNT; pidProfileIndex++) {
|
||||
for (uint32_t pidProfileIndex = 0; pidProfileIndex < PID_PROFILE_COUNT; pidProfileIndex++) {
|
||||
cliDumpPidProfile(pidProfileIndex, dumpMask);
|
||||
}
|
||||
cliPrintHashLine("restore original profile selection");
|
||||
|
|
|
@ -1012,6 +1012,7 @@ const clivalue_t valueTable[] = {
|
|||
#endif
|
||||
|
||||
{ "motor_output_limit", VAR_UINT8 | PROFILE_VALUE, .config.minmaxUnsigned = { MOTOR_OUTPUT_LIMIT_PERCENT_MIN, MOTOR_OUTPUT_LIMIT_PERCENT_MAX }, PG_PID_PROFILE, offsetof(pidProfile_t, motor_output_limit) },
|
||||
{ "auto_profile_cell_count", VAR_INT8 | PROFILE_VALUE, .config.minmax = { AUTO_PROFILE_CELL_COUNT_CHANGE, MAX_AUTO_DETECT_CELL_COUNT }, PG_PID_PROFILE, offsetof(pidProfile_t, auto_profile_cell_count) },
|
||||
|
||||
#ifdef USE_LAUNCH_CONTROL
|
||||
{ "launch_control_mode", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_LAUNCH_CONTROL_MODE }, PG_PID_PROFILE, offsetof(pidProfile_t, launchControlMode) },
|
||||
|
|
|
@ -52,6 +52,7 @@
|
|||
|
||||
#include "pg/pg.h"
|
||||
|
||||
#include "sensors/battery.h"
|
||||
#include "sensors/gyro.h"
|
||||
|
||||
|
||||
|
@ -326,6 +327,7 @@ static uint8_t cmsx_throttleBoost;
|
|||
static uint16_t cmsx_itermAcceleratorGain;
|
||||
static uint16_t cmsx_itermThrottleThreshold;
|
||||
static uint8_t cmsx_motorOutputLimit;
|
||||
static int8_t cmsx_autoProfileCellCount;
|
||||
|
||||
static long cmsx_profileOtherOnEnter(void)
|
||||
{
|
||||
|
@ -344,6 +346,7 @@ static long cmsx_profileOtherOnEnter(void)
|
|||
|
||||
cmsx_throttleBoost = pidProfile->throttle_boost;
|
||||
cmsx_motorOutputLimit = pidProfile->motor_output_limit;
|
||||
cmsx_autoProfileCellCount = pidProfile->auto_profile_cell_count;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
@ -365,6 +368,7 @@ static long cmsx_profileOtherOnExit(const OSD_Entry *self)
|
|||
|
||||
pidProfile->throttle_boost = cmsx_throttleBoost;
|
||||
pidProfile->motor_output_limit = cmsx_motorOutputLimit;
|
||||
pidProfile->auto_profile_cell_count = cmsx_autoProfileCellCount;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
@ -386,6 +390,8 @@ static OSD_Entry cmsx_menuProfileOtherEntries[] = {
|
|||
#endif
|
||||
{ "MTR OUT LIM %",OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_motorOutputLimit, MOTOR_OUTPUT_LIMIT_PERCENT_MIN, MOTOR_OUTPUT_LIMIT_PERCENT_MAX, 1}, 0 },
|
||||
|
||||
{ "AUTO CELL CNT", OME_INT8, NULL, &(OSD_INT8_t) { &cmsx_autoProfileCellCount, AUTO_PROFILE_CELL_COUNT_CHANGE, MAX_AUTO_DETECT_CELL_COUNT, 1}, 0 },
|
||||
|
||||
{ "BACK", OME_Back, NULL, NULL, 0 },
|
||||
{ NULL, OME_END, NULL, NULL, 0 }
|
||||
};
|
||||
|
@ -695,7 +701,7 @@ static OSD_Entry cmsx_menuImuEntries[] =
|
|||
{
|
||||
{ "-- PROFILE --", OME_Label, NULL, NULL, 0},
|
||||
|
||||
{"PID PROF", OME_UINT8, cmsx_profileIndexOnChange, &(OSD_UINT8_t){ &tmpPidProfileIndex, 1, MAX_PROFILE_COUNT, 1}, 0},
|
||||
{"PID PROF", OME_UINT8, cmsx_profileIndexOnChange, &(OSD_UINT8_t){ &tmpPidProfileIndex, 1, PID_PROFILE_COUNT, 1}, 0},
|
||||
{"PID", OME_Submenu, cmsMenuChange, &cmsx_menuPid, 0},
|
||||
{"MISC PP", OME_Submenu, cmsMenuChange, &cmsx_menuProfileOther, 0},
|
||||
{"FILT PP", OME_Submenu, cmsMenuChange, &cmsx_menuFilterPerProfile, 0},
|
||||
|
|
|
@ -192,7 +192,7 @@ static void validateAndFixConfig(void)
|
|||
}
|
||||
loadControlRateProfile();
|
||||
|
||||
if (systemConfig()->pidProfileIndex >= MAX_PROFILE_COUNT) {
|
||||
if (systemConfig()->pidProfileIndex >= PID_PROFILE_COUNT) {
|
||||
systemConfigMutable()->pidProfileIndex = 0;
|
||||
}
|
||||
loadPidProfile();
|
||||
|
@ -213,6 +213,10 @@ static void validateAndFixConfig(void)
|
|||
currentPidProfile->motor_output_limit = 100;
|
||||
}
|
||||
|
||||
if (currentPidProfile->auto_profile_cell_count > MAX_AUTO_DETECT_CELL_COUNT || currentPidProfile->auto_profile_cell_count < AUTO_PROFILE_CELL_COUNT_CHANGE) {
|
||||
currentPidProfile->auto_profile_cell_count = AUTO_PROFILE_CELL_COUNT_STAY;
|
||||
}
|
||||
|
||||
if (motorConfig()->dev.motorPwmProtocol == PWM_TYPE_BRUSHED) {
|
||||
featureDisable(FEATURE_3D);
|
||||
|
||||
|
@ -284,7 +288,7 @@ static void validateAndFixConfig(void)
|
|||
}
|
||||
|
||||
if (!rcSmoothingIsEnabled() || rxConfig()->rcInterpolationChannels == INTERPOLATION_CHANNELS_T) {
|
||||
for (unsigned i = 0; i < MAX_PROFILE_COUNT; i++) {
|
||||
for (unsigned i = 0; i < PID_PROFILE_COUNT; i++) {
|
||||
pidProfilesMutable(i)->pid[PID_ROLL].F = 0;
|
||||
pidProfilesMutable(i)->pid[PID_PITCH].F = 0;
|
||||
}
|
||||
|
@ -294,7 +298,7 @@ static void validateAndFixConfig(void)
|
|||
(rxConfig()->rcInterpolationChannels != INTERPOLATION_CHANNELS_RPY &&
|
||||
rxConfig()->rcInterpolationChannels != INTERPOLATION_CHANNELS_RPYT)) {
|
||||
|
||||
for (unsigned i = 0; i < MAX_PROFILE_COUNT; i++) {
|
||||
for (unsigned i = 0; i < PID_PROFILE_COUNT; i++) {
|
||||
pidProfilesMutable(i)->pid[PID_YAW].F = 0;
|
||||
}
|
||||
}
|
||||
|
@ -304,7 +308,7 @@ static void validateAndFixConfig(void)
|
|||
!(rxConfig()->rcInterpolationChannels == INTERPOLATION_CHANNELS_RPYT
|
||||
|| rxConfig()->rcInterpolationChannels == INTERPOLATION_CHANNELS_T
|
||||
|| rxConfig()->rcInterpolationChannels == INTERPOLATION_CHANNELS_RPT)) {
|
||||
for (unsigned i = 0; i < MAX_PROFILE_COUNT; i++) {
|
||||
for (unsigned i = 0; i < PID_PROFILE_COUNT; i++) {
|
||||
pidProfilesMutable(i)->throttle_boost = 0;
|
||||
}
|
||||
}
|
||||
|
@ -628,9 +632,34 @@ void saveConfigAndNotify(void)
|
|||
beeperConfirmationBeeps(1);
|
||||
}
|
||||
|
||||
void changePidProfileFromCellCount(uint8_t cellCount)
|
||||
{
|
||||
if (currentPidProfile->auto_profile_cell_count == cellCount || currentPidProfile->auto_profile_cell_count == AUTO_PROFILE_CELL_COUNT_STAY) {
|
||||
return;
|
||||
}
|
||||
|
||||
unsigned profileIndex = (systemConfig()->pidProfileIndex + 1) % PID_PROFILE_COUNT;
|
||||
int matchingProfileIndex = -1;
|
||||
while (profileIndex != systemConfig()->pidProfileIndex) {
|
||||
if (pidProfiles(profileIndex)->auto_profile_cell_count == cellCount) {
|
||||
matchingProfileIndex = profileIndex;
|
||||
|
||||
break;
|
||||
} else if (matchingProfileIndex < 0 && pidProfiles(profileIndex)->auto_profile_cell_count == AUTO_PROFILE_CELL_COUNT_STAY) {
|
||||
matchingProfileIndex = profileIndex;
|
||||
}
|
||||
|
||||
profileIndex = (profileIndex + 1) % PID_PROFILE_COUNT;
|
||||
}
|
||||
|
||||
if (matchingProfileIndex >= 0) {
|
||||
changePidProfile(matchingProfileIndex);
|
||||
}
|
||||
}
|
||||
|
||||
void changePidProfile(uint8_t pidProfileIndex)
|
||||
{
|
||||
if (pidProfileIndex < MAX_PROFILE_COUNT) {
|
||||
if (pidProfileIndex < PID_PROFILE_COUNT) {
|
||||
systemConfigMutable()->pidProfileIndex = pidProfileIndex;
|
||||
loadPidProfile();
|
||||
|
||||
|
|
|
@ -65,6 +65,7 @@ void validateAndFixGyroConfig(void);
|
|||
|
||||
uint8_t getCurrentPidProfileIndex(void);
|
||||
void changePidProfile(uint8_t pidProfileIndex);
|
||||
void changePidProfileFromCellCount(uint8_t cellCount);
|
||||
struct pidProfile_s;
|
||||
void resetPidProfile(struct pidProfile_s *profile);
|
||||
|
||||
|
|
|
@ -29,12 +29,10 @@
|
|||
#include "build/debug.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
#include "common/filter.h"
|
||||
#include "common/maths.h"
|
||||
|
||||
#include "config/config_reset.h"
|
||||
#include "pg/pg.h"
|
||||
#include "pg/pg_ids.h"
|
||||
|
||||
#include "drivers/sound_beeper.h"
|
||||
#include "drivers/time.h"
|
||||
|
@ -42,22 +40,25 @@
|
|||
#include "fc/controlrate_profile.h"
|
||||
#include "fc/core.h"
|
||||
#include "fc/rc.h"
|
||||
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/gps_rescue.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
|
||||
#include "io/gps.h"
|
||||
|
||||
#include "sensors/gyro.h"
|
||||
#include "sensors/acceleration.h"
|
||||
#include "pg/pg.h"
|
||||
#include "pg/pg_ids.h"
|
||||
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/battery.h"
|
||||
#include "sensors/gyro.h"
|
||||
#include "sensors/rpm_filter.h"
|
||||
|
||||
#include "pid.h"
|
||||
|
||||
const char pidNames[] =
|
||||
"ROLL;"
|
||||
"PITCH;"
|
||||
|
@ -119,7 +120,7 @@ PG_RESET_TEMPLATE(pidConfig_t, pidConfig,
|
|||
|
||||
#define LAUNCH_CONTROL_YAW_ITERM_LIMIT 50 // yaw iterm windup limit when launch mode is "FULL" (all axes)
|
||||
|
||||
PG_REGISTER_ARRAY_WITH_RESET_FN(pidProfile_t, MAX_PROFILE_COUNT, pidProfiles, PG_PID_PROFILE, 8);
|
||||
PG_REGISTER_ARRAY_WITH_RESET_FN(pidProfile_t, PID_PROFILE_COUNT, pidProfiles, PG_PID_PROFILE, 9);
|
||||
|
||||
void resetPidProfile(pidProfile_t *pidProfile)
|
||||
{
|
||||
|
@ -192,6 +193,7 @@ void resetPidProfile(pidProfile_t *pidProfile)
|
|||
.dterm_cut_range_hz = 40,
|
||||
.dterm_cut_lowpass_hz = 7,
|
||||
.motor_output_limit = 100,
|
||||
.auto_profile_cell_count = AUTO_PROFILE_CELL_COUNT_STAY,
|
||||
);
|
||||
#ifdef USE_DYN_LPF
|
||||
pidProfile->dterm_lowpass_hz = 150;
|
||||
|
@ -207,7 +209,7 @@ void resetPidProfile(pidProfile_t *pidProfile)
|
|||
|
||||
void pgResetFn_pidProfiles(pidProfile_t *pidProfiles)
|
||||
{
|
||||
for (int i = 0; i < MAX_PROFILE_COUNT; i++) {
|
||||
for (int i = 0; i < PID_PROFILE_COUNT; i++) {
|
||||
resetPidProfile(&pidProfiles[i]);
|
||||
}
|
||||
}
|
||||
|
@ -716,7 +718,7 @@ float pidApplyThrustLinearization(float motorOutput)
|
|||
|
||||
void pidCopyProfile(uint8_t dstPidProfileIndex, uint8_t srcPidProfileIndex)
|
||||
{
|
||||
if ((dstPidProfileIndex < MAX_PROFILE_COUNT-1 && srcPidProfileIndex < MAX_PROFILE_COUNT-1)
|
||||
if ((dstPidProfileIndex < PID_PROFILE_COUNT-1 && srcPidProfileIndex < PID_PROFILE_COUNT-1)
|
||||
&& dstPidProfileIndex != srcPidProfileIndex
|
||||
) {
|
||||
memcpy(pidProfilesMutable(dstPidProfileIndex), pidProfilesMutable(srcPidProfileIndex), sizeof(pidProfile_t));
|
||||
|
|
|
@ -165,9 +165,10 @@ typedef struct pidProfile_s {
|
|||
uint8_t dterm_cut_range_hz; // Biquad to prevent high frequency gyro noise from removing the dterm cut
|
||||
uint8_t dterm_cut_lowpass_hz; // First order lowpass to delay and smooth dterm cut factor
|
||||
uint8_t motor_output_limit; // Upper limit of the motor output (percent)
|
||||
int8_t auto_profile_cell_count; // Cell count for this profile to be used with if auto PID profile switching is used
|
||||
} pidProfile_t;
|
||||
|
||||
PG_DECLARE_ARRAY(pidProfile_t, MAX_PROFILE_COUNT, pidProfiles);
|
||||
PG_DECLARE_ARRAY(pidProfile_t, PID_PROFILE_COUNT, pidProfiles);
|
||||
|
||||
typedef struct pidConfig_s {
|
||||
uint8_t pid_process_denom; // Processing denominator for PID controller vs gyro sampling rate
|
||||
|
|
|
@ -824,7 +824,7 @@ static bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst)
|
|||
sbufWriteU8(dst, getCurrentPidProfileIndex());
|
||||
sbufWriteU16(dst, constrain(averageSystemLoadPercent, 0, 100));
|
||||
if (cmdMSP == MSP_STATUS_EX) {
|
||||
sbufWriteU8(dst, MAX_PROFILE_COUNT);
|
||||
sbufWriteU8(dst, PID_PROFILE_COUNT);
|
||||
sbufWriteU8(dst, getCurrentControlRateProfileIndex());
|
||||
} else { // MSP_STATUS
|
||||
sbufWriteU16(dst, 0); // gyro cycle time
|
||||
|
@ -1616,7 +1616,7 @@ static mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
|||
value = sbufReadU8(src);
|
||||
if ((value & RATEPROFILE_MASK) == 0) {
|
||||
if (!ARMING_FLAG(ARMED)) {
|
||||
if (value >= MAX_PROFILE_COUNT) {
|
||||
if (value >= PID_PROFILE_COUNT) {
|
||||
value = 0;
|
||||
}
|
||||
changePidProfile(value);
|
||||
|
|
|
@ -56,8 +56,6 @@
|
|||
*
|
||||
*/
|
||||
|
||||
static void batteryUpdateConsumptionState(void); // temporary forward reference
|
||||
|
||||
#define VBAT_STABLE_MAX_DELTA 20
|
||||
#define LVC_AFFECT_TIME 10000000 //10 secs for the LVC to slowly kick in
|
||||
|
||||
|
@ -168,44 +166,50 @@ static void updateBatteryBeeperAlert(void)
|
|||
}
|
||||
}
|
||||
|
||||
static bool isVoltageStable(void)
|
||||
{
|
||||
return ABS(voltageMeter.filtered - voltageMeter.unfiltered) <= VBAT_STABLE_MAX_DELTA;
|
||||
}
|
||||
|
||||
static bool isVoltageFromBat(void)
|
||||
{
|
||||
// We want to disable battery getting detected around USB voltage or 0V
|
||||
|
||||
return (voltageMeter.filtered >= batteryConfig()->vbatnotpresentcellvoltage // Above ~0V
|
||||
&& voltageMeter.filtered <= batteryConfig()->vbatmaxcellvoltage) // 1s max cell voltage check
|
||||
|| voltageMeter.filtered > batteryConfig()->vbatnotpresentcellvoltage * 2; // USB voltage - 2s or more check
|
||||
}
|
||||
|
||||
void batteryUpdatePresence(void)
|
||||
{
|
||||
bool isVoltageStable = ABS(voltageMeter.filtered - voltageMeter.unfiltered) <= VBAT_STABLE_MAX_DELTA;
|
||||
|
||||
bool isVoltageFromBat = (voltageMeter.filtered >= batteryConfig()->vbatnotpresentcellvoltage //above ~0V
|
||||
&& voltageMeter.filtered <= batteryConfig()->vbatmaxcellvoltage) //1s max cell voltage check
|
||||
|| voltageMeter.filtered > batteryConfig()->vbatnotpresentcellvoltage*2; //USB voltage - 2s or more check
|
||||
|
||||
|
||||
if (
|
||||
(voltageState == BATTERY_NOT_PRESENT || voltageState == BATTERY_INIT)
|
||||
&& isVoltageFromBat
|
||||
&& isVoltageStable
|
||||
(voltageState == BATTERY_NOT_PRESENT || voltageState == BATTERY_INIT) && isVoltageFromBat() && isVoltageStable()
|
||||
) {
|
||||
/* Want to disable battery getting detected around USB voltage or 0V*/
|
||||
/* battery has just been connected - calculate cells, warning voltages and reset state */
|
||||
|
||||
|
||||
// Battery has just been connected - calculate cells, warning voltages and reset state
|
||||
|
||||
consumptionState = voltageState = BATTERY_OK;
|
||||
if (batteryConfig()->forceBatteryCellCount != 0) {
|
||||
batteryCellCount = batteryConfig()->forceBatteryCellCount;
|
||||
} else {
|
||||
unsigned cells = (voltageMeter.filtered / batteryConfig()->vbatmaxcellvoltage) + 1;
|
||||
if (cells > 8) {
|
||||
// something is wrong, we expect 8 cells maximum (and autodetection will be problematic at 6+ cells)
|
||||
cells = 8;
|
||||
if (cells > MAX_AUTO_DETECT_CELL_COUNT) {
|
||||
// something is wrong, we expect MAX_CELL_COUNT cells maximum (and autodetection will be problematic at 6+ cells)
|
||||
cells = MAX_AUTO_DETECT_CELL_COUNT;
|
||||
}
|
||||
batteryCellCount = cells;
|
||||
|
||||
if (!ARMING_FLAG(ARMED)) {
|
||||
changePidProfileFromCellCount(batteryCellCount);
|
||||
}
|
||||
}
|
||||
batteryWarningVoltage = batteryCellCount * batteryConfig()->vbatwarningcellvoltage;
|
||||
batteryCriticalVoltage = batteryCellCount * batteryConfig()->vbatmincellvoltage;
|
||||
lowVoltageCutoff.percentage = 100;
|
||||
lowVoltageCutoff.startTime = 0;
|
||||
} else if (
|
||||
voltageState != BATTERY_NOT_PRESENT
|
||||
&& isVoltageStable
|
||||
&& !isVoltageFromBat
|
||||
voltageState != BATTERY_NOT_PRESENT && isVoltageStable() && !isVoltageFromBat()
|
||||
) {
|
||||
/* battery has been disconnected - can take a while for filter cap to disharge so we use a threshold of batteryConfig()->vbatnotpresentcellvoltage */
|
||||
|
||||
|
@ -217,7 +221,7 @@ void batteryUpdatePresence(void)
|
|||
}
|
||||
if (debugMode == DEBUG_BATTERY) {
|
||||
debug[2] = batteryCellCount;
|
||||
debug[3] = isVoltageStable;
|
||||
debug[3] = isVoltageStable();
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -271,6 +275,21 @@ static void batteryUpdateLVC(timeUs_t currentTimeUs)
|
|||
|
||||
}
|
||||
|
||||
static void batteryUpdateConsumptionState(void)
|
||||
{
|
||||
if (batteryConfig()->useConsumptionAlerts && batteryConfig()->batteryCapacity > 0 && batteryCellCount > 0) {
|
||||
uint8_t batteryPercentageRemaining = calculateBatteryPercentageRemaining();
|
||||
|
||||
if (batteryPercentageRemaining == 0) {
|
||||
consumptionState = BATTERY_CRITICAL;
|
||||
} else if (batteryPercentageRemaining <= batteryConfig()->consumptionWarningPercentage) {
|
||||
consumptionState = BATTERY_WARNING;
|
||||
} else {
|
||||
consumptionState = BATTERY_OK;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void batteryUpdateStates(timeUs_t currentTimeUs)
|
||||
{
|
||||
batteryUpdateVoltageState();
|
||||
|
@ -373,21 +392,6 @@ void batteryInit(void)
|
|||
|
||||
}
|
||||
|
||||
static void batteryUpdateConsumptionState(void)
|
||||
{
|
||||
if (batteryConfig()->useConsumptionAlerts && batteryConfig()->batteryCapacity > 0 && batteryCellCount > 0) {
|
||||
uint8_t batteryPercentageRemaining = calculateBatteryPercentageRemaining();
|
||||
|
||||
if (batteryPercentageRemaining == 0) {
|
||||
consumptionState = BATTERY_CRITICAL;
|
||||
} else if (batteryPercentageRemaining <= batteryConfig()->consumptionWarningPercentage) {
|
||||
consumptionState = BATTERY_WARNING;
|
||||
} else {
|
||||
consumptionState = BATTERY_OK;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void batteryUpdateCurrentMeter(timeUs_t currentTimeUs)
|
||||
{
|
||||
UNUSED(currentTimeUs);
|
||||
|
|
|
@ -30,8 +30,15 @@
|
|||
#define VBAT_CELL_VOTAGE_RANGE_MIN 100
|
||||
#define VBAT_CELL_VOTAGE_RANGE_MAX 500
|
||||
|
||||
#define MAX_AUTO_DETECT_CELL_COUNT 8
|
||||
|
||||
#define GET_BATTERY_LPF_FREQUENCY(period) (1.0f / (period / 10))
|
||||
|
||||
enum {
|
||||
AUTO_PROFILE_CELL_COUNT_STAY = 0, // Stay on this profile irrespective of the detected cell count. Use this profile if no other profile matches (default, i.e. auto profile switching is off)
|
||||
AUTO_PROFILE_CELL_COUNT_CHANGE = -1, // Always switch to a profile with matching cell count if there is one
|
||||
};
|
||||
|
||||
typedef struct batteryConfig_s {
|
||||
// voltage
|
||||
uint16_t vbatmaxcellvoltage; // maximum voltage per cell, used for auto-detecting battery voltage in 0.01V units, default is 430 (4.30V)
|
||||
|
|
|
@ -54,7 +54,7 @@ void targetConfiguration(void)
|
|||
motorConfigMutable()->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
|
||||
}
|
||||
|
||||
for (uint8_t pidProfileIndex = 0; pidProfileIndex < MAX_PROFILE_COUNT; pidProfileIndex++) {
|
||||
for (uint8_t pidProfileIndex = 0; pidProfileIndex < PID_PROFILE_COUNT; pidProfileIndex++) {
|
||||
pidProfile_t *pidProfile = pidProfilesMutable(pidProfileIndex);
|
||||
|
||||
pidProfile->pid[PID_ROLL].P = 90;
|
||||
|
|
|
@ -115,7 +115,7 @@ void targetConfiguration(void)
|
|||
pidConfigMutable()->pid_process_denom = 1;
|
||||
}
|
||||
|
||||
for (uint8_t pidProfileIndex = 0; pidProfileIndex < MAX_PROFILE_COUNT; pidProfileIndex++) {
|
||||
for (uint8_t pidProfileIndex = 0; pidProfileIndex < PID_PROFILE_COUNT; pidProfileIndex++) {
|
||||
pidProfile_t *pidProfile = pidProfilesMutable(pidProfileIndex);
|
||||
|
||||
pidProfile->pid[PID_ROLL].P = 90;
|
||||
|
|
|
@ -76,7 +76,7 @@ void targetConfiguration(void)
|
|||
featureEnable(FEATURE_TELEMETRY);
|
||||
}
|
||||
|
||||
for (uint8_t pidProfileIndex = 0; pidProfileIndex < MAX_PROFILE_COUNT; pidProfileIndex++) {
|
||||
for (uint8_t pidProfileIndex = 0; pidProfileIndex < PID_PROFILE_COUNT; pidProfileIndex++) {
|
||||
pidProfile_t *pidProfile = pidProfilesMutable(pidProfileIndex);
|
||||
|
||||
pidProfile->pid[PID_ROLL].P = 53;
|
||||
|
|
|
@ -75,7 +75,7 @@ void targetConfiguration(void)
|
|||
featureEnable(FEATURE_TELEMETRY);
|
||||
}
|
||||
|
||||
for (uint8_t pidProfileIndex = 0; pidProfileIndex < MAX_PROFILE_COUNT; pidProfileIndex++) {
|
||||
for (uint8_t pidProfileIndex = 0; pidProfileIndex < PID_PROFILE_COUNT; pidProfileIndex++) {
|
||||
pidProfile_t *pidProfile = pidProfilesMutable(pidProfileIndex);
|
||||
|
||||
pidProfile->pid[FD_ROLL].P = 53;
|
||||
|
|
|
@ -116,7 +116,7 @@ void targetConfiguration(void)
|
|||
featureEnable((FEATURE_DYNAMIC_FILTER | FEATURE_AIRMODE | FEATURE_ANTI_GRAVITY) ^ FEATURE_RX_PARALLEL_PWM);
|
||||
|
||||
/* AlienWhoop PIDs tested with 6mm and 7mm motors on most frames */
|
||||
for (uint8_t pidProfileIndex = 0; pidProfileIndex < MAX_PROFILE_COUNT; pidProfileIndex++) {
|
||||
for (uint8_t pidProfileIndex = 0; pidProfileIndex < PID_PROFILE_COUNT; pidProfileIndex++) {
|
||||
pidProfile_t *pidProfile = pidProfilesMutable(pidProfileIndex);
|
||||
|
||||
pidProfile->pidSumLimit = 1000;
|
||||
|
|
|
@ -73,7 +73,7 @@ void targetConfiguration(void)
|
|||
pidConfigMutable()->pid_process_denom = 1;
|
||||
}
|
||||
|
||||
for (uint8_t pidProfileIndex = 0; pidProfileIndex < MAX_PROFILE_COUNT; pidProfileIndex++) {
|
||||
for (uint8_t pidProfileIndex = 0; pidProfileIndex < PID_PROFILE_COUNT; pidProfileIndex++) {
|
||||
pidProfile_t *pidProfile = pidProfilesMutable(pidProfileIndex);
|
||||
|
||||
pidProfile->pid[PID_ROLL].P = 86;
|
||||
|
|
|
@ -69,7 +69,7 @@ void targetConfiguration(void)
|
|||
#endif
|
||||
parseRcChannels("TAER1234", rxConfigMutable());
|
||||
|
||||
for (uint8_t pidProfileIndex = 0; pidProfileIndex < MAX_PROFILE_COUNT; pidProfileIndex++) {
|
||||
for (uint8_t pidProfileIndex = 0; pidProfileIndex < PID_PROFILE_COUNT; pidProfileIndex++) {
|
||||
pidProfile_t *pidProfile = pidProfilesMutable(pidProfileIndex);
|
||||
|
||||
pidProfile->pid[PID_ROLL].P = 80;
|
||||
|
|
|
@ -82,7 +82,7 @@ void targetConfiguration(void)
|
|||
gyroConfigMutable()->gyro_sync_denom = 4;
|
||||
pidConfigMutable()->pid_process_denom = 1;
|
||||
|
||||
for (uint8_t pidProfileIndex = 0; pidProfileIndex < MAX_PROFILE_COUNT; pidProfileIndex++) {
|
||||
for (uint8_t pidProfileIndex = 0; pidProfileIndex < PID_PROFILE_COUNT; pidProfileIndex++) {
|
||||
pidProfile_t *pidProfile = pidProfilesMutable(pidProfileIndex);
|
||||
|
||||
pidProfile->pid[PID_ROLL].P = 70;
|
||||
|
|
|
@ -73,7 +73,7 @@ void targetConfiguration(void)
|
|||
rxChannelRangeConfigsMutable(channel)->max = 1860;
|
||||
}*/
|
||||
|
||||
for (uint8_t pidProfileIndex = 0; pidProfileIndex < MAX_PROFILE_COUNT; pidProfileIndex++) {
|
||||
for (uint8_t pidProfileIndex = 0; pidProfileIndex < PID_PROFILE_COUNT; pidProfileIndex++) {
|
||||
pidProfile_t *pidProfile = pidProfilesMutable(pidProfileIndex);
|
||||
|
||||
pidProfile->pid[PID_ROLL].P = 60;
|
||||
|
|
|
@ -47,7 +47,7 @@ void targetConfiguration(void)
|
|||
|
||||
motorConfigMutable()->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
|
||||
|
||||
for (uint8_t pidProfileIndex = 0; pidProfileIndex < MAX_PROFILE_COUNT; pidProfileIndex++) {
|
||||
for (uint8_t pidProfileIndex = 0; pidProfileIndex < PID_PROFILE_COUNT; pidProfileIndex++) {
|
||||
pidProfile_t *pidProfile = pidProfilesMutable(pidProfileIndex);
|
||||
|
||||
pidProfile->pid[FD_ROLL].P = 90;
|
||||
|
|
|
@ -62,7 +62,7 @@ void targetConfiguration(void)
|
|||
}
|
||||
|
||||
/* Specific PID values for YupiF4 */
|
||||
for (uint8_t pidProfileIndex = 0; pidProfileIndex < MAX_PROFILE_COUNT; pidProfileIndex++) {
|
||||
for (uint8_t pidProfileIndex = 0; pidProfileIndex < PID_PROFILE_COUNT; pidProfileIndex++) {
|
||||
pidProfile_t *pidProfile = pidProfilesMutable(pidProfileIndex);
|
||||
|
||||
pidProfile->pid[PID_ROLL].P = 30;
|
||||
|
|
|
@ -146,9 +146,9 @@
|
|||
#define USE_SERIALRX_SUMD // Graupner Hott protocol
|
||||
|
||||
#if (FLASH_SIZE > 64)
|
||||
#define MAX_PROFILE_COUNT 3
|
||||
#define PID_PROFILE_COUNT 3
|
||||
#else
|
||||
#define MAX_PROFILE_COUNT 2
|
||||
#define PID_PROFILE_COUNT 2
|
||||
#endif
|
||||
|
||||
#if (FLASH_SIZE > 64)
|
||||
|
|
|
@ -32,7 +32,7 @@
|
|||
#define FAST_RAM_ZERO_INIT
|
||||
#define FAST_RAM
|
||||
|
||||
#define MAX_PROFILE_COUNT 3
|
||||
#define PID_PROFILE_COUNT 3
|
||||
#define USE_MAG
|
||||
#define USE_BARO
|
||||
#define USE_GPS
|
||||
|
|
Loading…
Reference in New Issue