mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-23 08:15:30 +03:00
New Clli params RC Smoothing and sync_gyro_to_loop
This commit is contained in:
parent
259630840a
commit
41895bc1af
9 changed files with 78 additions and 51 deletions
|
@ -449,8 +449,10 @@ static void resetConf(void)
|
|||
|
||||
resetSerialConfig(&masterConfig.serialConfig);
|
||||
|
||||
masterConfig.looptime = 3500;
|
||||
masterConfig.looptime = 2000;
|
||||
masterConfig.emf_avoidance = 0;
|
||||
masterConfig.syncGyroToLoop = 1;
|
||||
masterConfig.rcSmoothing = 1;
|
||||
|
||||
resetPidProfile(¤tProfile->pidProfile);
|
||||
|
||||
|
@ -540,6 +542,7 @@ static void resetConf(void)
|
|||
masterConfig.escAndServoConfig.maxthrottle = 2000;
|
||||
masterConfig.motor_pwm_rate = 32000;
|
||||
masterConfig.looptime = 2000;
|
||||
masterConfig.rcSmoothing = 1;
|
||||
currentProfile->pidProfile.pidController = 3;
|
||||
currentProfile->pidProfile.P8[ROLL] = 36;
|
||||
currentProfile->pidProfile.P8[PITCH] = 36;
|
||||
|
|
|
@ -27,6 +27,8 @@ typedef struct master_t {
|
|||
uint32_t enabledFeatures;
|
||||
uint16_t looptime; // imu loop time in us
|
||||
uint8_t emf_avoidance; // change pll settings to avoid noise in the uhf band
|
||||
uint8_t syncGyroToLoop; // Enable interrupt based loop
|
||||
uint8_t rcSmoothing; // Enable Interpolation of RC command
|
||||
|
||||
motorMixer_t customMotorMixer[MAX_SUPPORTED_MOTORS];
|
||||
#ifdef USE_SERVOS
|
||||
|
|
|
@ -43,10 +43,11 @@ bool gyroSyncCheckUpdate(void) {
|
|||
return getMpuInterrupt(&gyro);
|
||||
}
|
||||
|
||||
void gyroUpdateSampleRate(uint32_t looptime, uint8_t lpf) {
|
||||
void gyroUpdateSampleRate(uint32_t looptime, uint8_t lpf, uint8_t syncGyroToLoop) {
|
||||
int gyroSamplePeriod;
|
||||
int minLooptime;
|
||||
|
||||
if (syncGyroToLoop) {
|
||||
#ifdef STM32F303xC
|
||||
if (lpf == INV_FILTER_256HZ_NOLPF2) {
|
||||
gyroSamplePeriod = 125;
|
||||
|
@ -86,6 +87,11 @@ void gyroUpdateSampleRate(uint32_t looptime, uint8_t lpf) {
|
|||
looptime = constrain(looptime, minLooptime, 4000);
|
||||
mpuDivider = (looptime + gyroSamplePeriod -1 ) / gyroSamplePeriod - 1;
|
||||
targetLooptime = (mpuDivider + 1) * gyroSamplePeriod;
|
||||
}
|
||||
else {
|
||||
mpuDivider = 0;
|
||||
targetLooptime = looptime;
|
||||
}
|
||||
}
|
||||
|
||||
uint8_t gyroMPU6xxxGetDivider(void) {
|
||||
|
|
|
@ -9,4 +9,4 @@ extern uint32_t targetLooptime;
|
|||
|
||||
bool gyroSyncCheckUpdate(void);
|
||||
uint8_t gyroMPU6xxxGetDivider(void);
|
||||
void gyroUpdateSampleRate(uint32_t looptime, uint8_t lpf);
|
||||
void gyroUpdateSampleRate(uint32_t looptime, uint8_t lpf, uint8_t syncGyroToLoop);
|
||||
|
|
|
@ -315,8 +315,10 @@ typedef struct {
|
|||
} clivalue_t;
|
||||
|
||||
const clivalue_t valueTable[] = {
|
||||
{ "looptime", VAR_UINT16 | MASTER_VALUE, &masterConfig.looptime, 0, 9000 },
|
||||
{ "looptime", VAR_UINT16 | MASTER_VALUE, &masterConfig.looptime, 0, 4000 },
|
||||
{ "sync_gyro_to_loop", VAR_UINT8 | MASTER_VALUE, &masterConfig.syncGyroToLoop, 0, 1 },
|
||||
{ "emf_avoidance", VAR_UINT8 | MASTER_VALUE, &masterConfig.emf_avoidance, 0, 1 },
|
||||
{ "rc_smoothing", VAR_UINT8 | MASTER_VALUE, &masterConfig.rcSmoothing, 0, 1 },
|
||||
|
||||
{ "mid_rc", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.midrc, 1200, 1700 },
|
||||
{ "min_check", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.mincheck, PWM_RANGE_ZERO, PWM_RANGE_MAX },
|
||||
|
@ -2146,7 +2148,7 @@ static void cliVersion(char *cmdline)
|
|||
{
|
||||
UNUSED(cmdline);
|
||||
|
||||
printf("# Betaflight/%s %s %s / %s (%s)",
|
||||
printf("# BetaFlight/%s %s %s / %s (%s)",
|
||||
targetName,
|
||||
FC_VERSION_STRING,
|
||||
buildDate,
|
||||
|
|
|
@ -371,7 +371,7 @@ void init(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
if (!sensorsAutodetect(&masterConfig.sensorAlignmentConfig, masterConfig.gyro_lpf, masterConfig.acc_hardware, masterConfig.mag_hardware, currentProfile->mag_declination, masterConfig.looptime)) {
|
||||
if (!sensorsAutodetect(&masterConfig.sensorAlignmentConfig, masterConfig.gyro_lpf, masterConfig.acc_hardware, masterConfig.mag_hardware, currentProfile->mag_declination, masterConfig.looptime, masterConfig.syncGyroToLoop)) {
|
||||
// if gyro was not detected due to whatever reason, we give up now.
|
||||
failureMode(3);
|
||||
}
|
||||
|
|
|
@ -93,7 +93,6 @@ enum {
|
|||
/* IBat monitoring interval (in microseconds) - 6 default looptimes */
|
||||
#define IBATINTERVAL (6 * 3500)
|
||||
#define GYRO_WATCHDOG_DELAY 500 // Watchdog for boards without interrupt for gyro
|
||||
|
||||
#define LOOP_DEADBAND 400 // Dead band for loop to modify to rcInterpolationFactor in RC Filtering for unstable looptimes
|
||||
|
||||
uint32_t currentTime = 0;
|
||||
|
@ -693,19 +692,8 @@ void filterGyro(void) {
|
|||
static filterStatePt1_t gyroADCState[XYZ_AXIS_COUNT];
|
||||
|
||||
for (axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
|
||||
if (masterConfig.looptime > 0) {
|
||||
// Static dT calculation based on configured looptime
|
||||
if (!gyroADCState[axis].constdT) {
|
||||
gyroADCState[axis].constdT = (float)masterConfig.looptime * 0.000001f;
|
||||
}
|
||||
|
||||
gyroADC[axis] = filterApplyPt1(gyroADC[axis], &gyroADCState[axis], currentProfile->pidProfile.gyro_cut_hz, gyroADCState[axis].constdT);
|
||||
}
|
||||
|
||||
else {
|
||||
gyroADC[axis] = filterApplyPt1(gyroADC[axis], &gyroADCState[axis], currentProfile->pidProfile.gyro_cut_hz, dT);
|
||||
}
|
||||
}
|
||||
}
|
||||
void getArmingChannel(modeActivationCondition_t *modeActivationConditions, uint8_t *armingChannel) {
|
||||
for (int index = 0; index < MAX_MODE_ACTIVATION_CONDITION_COUNT; index++) {
|
||||
|
@ -813,6 +801,29 @@ void filterRc(void){
|
|||
}
|
||||
}
|
||||
|
||||
// Function for loop trigger
|
||||
bool runLoop(uint32_t loopTime) {
|
||||
bool loopTrigger = false;
|
||||
|
||||
if (masterConfig.syncGyroToLoop) {
|
||||
if (ARMING_FLAG(ARMED)) {
|
||||
if (gyroSyncCheckUpdate() || (int32_t)(currentTime - loopTime + GYRO_WATCHDOG_DELAY) >= 0) {
|
||||
loopTrigger = true;
|
||||
}
|
||||
}
|
||||
// Blheli arming workaround (stable looptime prior to arming)
|
||||
else if (!ARMING_FLAG(ARMED) && ((int32_t)(currentTime - loopTime) >= 0)) {
|
||||
loopTrigger = true;
|
||||
}
|
||||
}
|
||||
|
||||
else if ((int32_t)(currentTime - loopTime) >= 0){
|
||||
loopTrigger = true;
|
||||
}
|
||||
|
||||
return loopTrigger;
|
||||
}
|
||||
|
||||
void loop(void)
|
||||
{
|
||||
static uint32_t loopTime;
|
||||
|
@ -859,8 +870,9 @@ void loop(void)
|
|||
}
|
||||
|
||||
currentTime = micros();
|
||||
if (gyroSyncCheckUpdate() || (int32_t)(currentTime - loopTime) >= 0) {
|
||||
loopTime = currentTime + targetLooptime + GYRO_WATCHDOG_DELAY;
|
||||
if (runLoop(loopTime)) {
|
||||
|
||||
loopTime = currentTime + targetLooptime;
|
||||
|
||||
imuUpdate(¤tProfile->accelerometerTrims);
|
||||
|
||||
|
@ -875,7 +887,9 @@ void loop(void)
|
|||
filterGyro();
|
||||
}
|
||||
|
||||
if (masterConfig.rcSmoothing) {
|
||||
filterRc();
|
||||
}
|
||||
|
||||
annexCode();
|
||||
#if defined(BARO) || defined(SONAR)
|
||||
|
|
|
@ -597,7 +597,7 @@ void reconfigureAlignment(sensorAlignmentConfig_t *sensorAlignmentConfig)
|
|||
}
|
||||
}
|
||||
|
||||
bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint16_t gyroLpf, uint8_t accHardwareToUse, uint8_t magHardwareToUse, int16_t magDeclinationFromConfig, uint32_t looptime)
|
||||
bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint16_t gyroLpf, uint8_t accHardwareToUse, uint8_t magHardwareToUse, int16_t magDeclinationFromConfig, uint32_t looptime, uint8_t syncGyroToLoop)
|
||||
{
|
||||
int16_t deg, min;
|
||||
|
||||
|
@ -615,7 +615,7 @@ bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint16_t
|
|||
if (sensors(SENSOR_ACC))
|
||||
acc.init();
|
||||
// this is safe because either mpu6050 or mpu3050 or lg3d20 sets it, and in case of fail, we never get here.
|
||||
gyroUpdateSampleRate(looptime, gyroLpf); // Set gyro refresh rate before initialisation
|
||||
gyroUpdateSampleRate(looptime, gyroLpf, syncGyroToLoop); // Set gyro refresh rate before initialisation
|
||||
gyro.init();
|
||||
|
||||
detectMag(magHardwareToUse);
|
||||
|
|
|
@ -17,4 +17,4 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint16_t gyroLpf, uint8_t accHardwareToUse, uint8_t magHardwareToUse, int16_t magDeclinationFromConfig, uint32_t looptime);
|
||||
bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint16_t gyroLpf, uint8_t accHardwareToUse, uint8_t magHardwareToUse, int16_t magDeclinationFromConfig, uint32_t looptime, uint8_t syncGyroToLoop);
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue