Merge pull request #1775 from betaflight/major_mw_cleanup

Cleanup mw.c // Remove unnecessary functions
This commit is contained in:
borisbstyle 2016-12-30 15:16:49 +01:00 committed by GitHub
commit 21463656c7
19 changed files with 155 additions and 449 deletions

View File

@ -524,7 +524,7 @@ COMMON_SRC = \
fc/config.c \ fc/config.c \
fc/fc_tasks.c \ fc/fc_tasks.c \
fc/fc_msp.c \ fc/fc_msp.c \
fc/mw.c \ fc/fc_main.c \
fc/rc_controls.c \ fc/rc_controls.c \
fc/rc_curves.c \ fc/rc_curves.c \
fc/runtime_config.c \ fc/runtime_config.c \
@ -586,7 +586,6 @@ HIGHEND_SRC = \
drivers/serial_escserial.c \ drivers/serial_escserial.c \
drivers/serial_softserial.c \ drivers/serial_softserial.c \
drivers/sonar_hcsr04.c \ drivers/sonar_hcsr04.c \
flight/gtune.c \
flight/navigation.c \ flight/navigation.c \
flight/gps_conversion.c \ flight/gps_conversion.c \
io/dashboard.c \ io/dashboard.c \

View File

@ -1258,11 +1258,11 @@ static bool blackboxWriteSysinfo()
BLACKBOX_PRINT_HEADER_LINE("pidAtMinThrottle:%d", currentProfile->pidProfile.pidAtMinThrottle); BLACKBOX_PRINT_HEADER_LINE("pidAtMinThrottle:%d", currentProfile->pidProfile.pidAtMinThrottle);
// Betaflight PID controller parameters // Betaflight PID controller parameters
BLACKBOX_PRINT_HEADER_LINE("itermThrottleGain:%d", currentProfile->pidProfile.itermThrottleGain); BLACKBOX_PRINT_HEADER_LINE("itermThrottleThreshold:%d", currentProfile->pidProfile.itermThrottleThreshold);
BLACKBOX_PRINT_HEADER_LINE("setpointRelaxRatio:%d", currentProfile->pidProfile.setpointRelaxRatio); BLACKBOX_PRINT_HEADER_LINE("setpointRelaxRatio:%d", currentProfile->pidProfile.setpointRelaxRatio);
BLACKBOX_PRINT_HEADER_LINE("dtermSetpointWeight:%d", currentProfile->pidProfile.dtermSetpointWeight); BLACKBOX_PRINT_HEADER_LINE("dtermSetpointWeight:%d", currentProfile->pidProfile.dtermSetpointWeight);
BLACKBOX_PRINT_HEADER_LINE("yawRateAccelLimit:%d", currentProfile->pidProfile.yawRateAccelLimit); BLACKBOX_PRINT_HEADER_LINE("yawRateAccelLimit:%d", castFloatBytesToInt(currentProfile->pidProfile.yawRateAccelLimit));
BLACKBOX_PRINT_HEADER_LINE("rateAccelLimit:%d", currentProfile->pidProfile.rateAccelLimit); BLACKBOX_PRINT_HEADER_LINE("rateAccelLimit:%d", castFloatBytesToInt(currentProfile->pidProfile.rateAccelLimit));
// End of Betaflight controller parameters // End of Betaflight controller parameters
BLACKBOX_PRINT_HEADER_LINE("deadband:%d", rcControlsConfig()->deadband); BLACKBOX_PRINT_HEADER_LINE("deadband:%d", rcControlsConfig()->deadband);
@ -1330,11 +1330,6 @@ void blackboxLogEvent(FlightLogEvent event, flightLogEventData_t *data)
blackboxWriteSignedVB(data->inflightAdjustment.newValue); blackboxWriteSignedVB(data->inflightAdjustment.newValue);
} }
break; break;
case FLIGHT_LOG_EVENT_GTUNE_RESULT:
blackboxWrite(data->gtuneCycleResult.gtuneAxis);
blackboxWriteSignedVB(data->gtuneCycleResult.gtuneGyroAVG);
blackboxWriteS16(data->gtuneCycleResult.gtuneNewP);
break;
case FLIGHT_LOG_EVENT_LOGGING_RESUME: case FLIGHT_LOG_EVENT_LOGGING_RESUME:
blackboxWriteUnsignedVB(data->loggingResume.logIteration); blackboxWriteUnsignedVB(data->loggingResume.logIteration);
blackboxWriteUnsignedVB(data->loggingResume.currentTime); blackboxWriteUnsignedVB(data->loggingResume.currentTime);

View File

@ -106,7 +106,6 @@ typedef enum FlightLogEvent {
FLIGHT_LOG_EVENT_SYNC_BEEP = 0, FLIGHT_LOG_EVENT_SYNC_BEEP = 0,
FLIGHT_LOG_EVENT_INFLIGHT_ADJUSTMENT = 13, FLIGHT_LOG_EVENT_INFLIGHT_ADJUSTMENT = 13,
FLIGHT_LOG_EVENT_LOGGING_RESUME = 14, FLIGHT_LOG_EVENT_LOGGING_RESUME = 14,
FLIGHT_LOG_EVENT_GTUNE_RESULT = 20,
FLIGHT_LOG_EVENT_FLIGHTMODE = 30, // Add new event type for flight mode status. FLIGHT_LOG_EVENT_FLIGHTMODE = 30, // Add new event type for flight mode status.
FLIGHT_LOG_EVENT_LOG_END = 255 FLIGHT_LOG_EVENT_LOG_END = 255
} FlightLogEvent; } FlightLogEvent;

View File

@ -30,7 +30,6 @@
#define PG_CONTROL_RATE_PROFILES 12 // struct OK, needs to be split out of rc_controls.h into rate_profile.h #define PG_CONTROL_RATE_PROFILES 12 // struct OK, needs to be split out of rc_controls.h into rate_profile.h
#define PG_SERIAL_CONFIG 13 // struct OK #define PG_SERIAL_CONFIG 13 // struct OK
#define PG_PID_PROFILE 14 // struct OK, CF differences #define PG_PID_PROFILE 14 // struct OK, CF differences
#define PG_GTUNE_CONFIG 15 // is GTUNE still being used?
#define PG_ARMING_CONFIG 16 // structs OK, CF naming differences #define PG_ARMING_CONFIG 16 // structs OK, CF naming differences
#define PG_TRANSPONDER_CONFIG 17 // struct OK #define PG_TRANSPONDER_CONFIG 17 // struct OK
#define PG_SYSTEM_CONFIG 18 // just has i2c_highspeed #define PG_SYSTEM_CONFIG 18 // just has i2c_highspeed

View File

@ -168,34 +168,23 @@ static void resetPidProfile(pidProfile_t *pidProfile)
pidProfile->yaw_p_limit = YAW_P_LIMIT_MAX; pidProfile->yaw_p_limit = YAW_P_LIMIT_MAX;
pidProfile->pidSumLimit = PIDSUM_LIMIT; pidProfile->pidSumLimit = PIDSUM_LIMIT;
pidProfile->yaw_lpf_hz = 0; pidProfile->yaw_lpf_hz = 0;
pidProfile->rollPitchItermIgnoreRate = 130; pidProfile->rollPitchItermIgnoreRate = 200;
pidProfile->yawItermIgnoreRate = 32; pidProfile->yawItermIgnoreRate = 55;
pidProfile->dterm_filter_type = FILTER_BIQUAD; pidProfile->dterm_filter_type = FILTER_BIQUAD;
pidProfile->dterm_lpf_hz = 100; // filtering ON by default pidProfile->dterm_lpf_hz = 100; // filtering ON by default
pidProfile->dterm_notch_hz = 260; pidProfile->dterm_notch_hz = 260;
pidProfile->dterm_notch_cutoff = 160; pidProfile->dterm_notch_cutoff = 160;
pidProfile->vbatPidCompensation = 0; pidProfile->vbatPidCompensation = 0;
pidProfile->pidAtMinThrottle = PID_STABILISATION_ON; pidProfile->pidAtMinThrottle = PID_STABILISATION_ON;
pidProfile->max_angle_inclination = 70.0f; // 70 degrees
// Betaflight PID controller parameters // Betaflight PID controller parameters
pidProfile->setpointRelaxRatio = 30; pidProfile->setpointRelaxRatio = 30;
pidProfile->dtermSetpointWeight = 200; pidProfile->dtermSetpointWeight = 200;
pidProfile->yawRateAccelLimit = 220; pidProfile->yawRateAccelLimit = 20.0f;
pidProfile->rateAccelLimit = 0; pidProfile->rateAccelLimit = 0.0f;
pidProfile->itermThrottleGain = 0; pidProfile->itermThrottleThreshold = 350;
pidProfile->levelSensitivity = 2.0f; pidProfile->levelSensitivity = 2.0f;
#ifdef GTUNE
pidProfile->gtune_lolimP[ROLL] = 10; // [0..200] Lower limit of ROLL P during G tune.
pidProfile->gtune_lolimP[PITCH] = 10; // [0..200] Lower limit of PITCH P during G tune.
pidProfile->gtune_lolimP[YAW] = 10; // [0..200] Lower limit of YAW P during G tune.
pidProfile->gtune_hilimP[ROLL] = 100; // [0..200] Higher limit of ROLL P during G tune. 0 Disables tuning for that axis.
pidProfile->gtune_hilimP[PITCH] = 100; // [0..200] Higher limit of PITCH P during G tune. 0 Disables tuning for that axis.
pidProfile->gtune_hilimP[YAW] = 100; // [0..200] Higher limit of YAW P during G tune. 0 Disables tuning for that axis.
pidProfile->gtune_pwr = 0; // [0..10] Strength of adjustment
pidProfile->gtune_settle_time = 450; // [200..1000] Settle time in ms
pidProfile->gtune_average_cycles = 16; // [8..128] Number of looptime cycles used for gyro average calculation
#endif
} }
void resetProfile(profile_t *profile) void resetProfile(profile_t *profile)
@ -624,7 +613,6 @@ void createDefaultConfig(master_t *config)
config->gyroConfig.gyro_sync_denom = 4; config->gyroConfig.gyro_sync_denom = 4;
config->pidConfig.pid_process_denom = 2; config->pidConfig.pid_process_denom = 2;
#endif #endif
config->pidConfig.max_angle_inclination = 700; // 70 degrees
config->gyroConfig.gyro_soft_lpf_type = FILTER_PT1; config->gyroConfig.gyro_soft_lpf_type = FILTER_PT1;
config->gyroConfig.gyro_soft_lpf_hz = 90; config->gyroConfig.gyro_soft_lpf_hz = 90;
config->gyroConfig.gyro_soft_notch_hz_1 = 400; config->gyroConfig.gyro_soft_notch_hz_1 = 400;

View File

@ -63,7 +63,6 @@
#include "flight/servos.h" #include "flight/servos.h"
#include "flight/pid.h" #include "flight/pid.h"
#include "flight/failsafe.h" #include "flight/failsafe.h"
#include "flight/gtune.h"
#include "flight/altitudehold.h" #include "flight/altitudehold.h"
#include "config/config_profile.h" #include "config/config_profile.h"
@ -93,13 +92,25 @@ uint8_t motorControlEnable = false;
int16_t telemTemperature1; // gyro sensor temperature int16_t telemTemperature1; // gyro sensor temperature
static uint32_t disarmAt; // Time of automatic disarm when "Don't spin the motors when armed" is enabled and auto_disarm_delay is nonzero static uint32_t disarmAt; // Time of automatic disarm when "Don't spin the motors when armed" is enabled and auto_disarm_delay is nonzero
extern uint8_t PIDweight[3]; static float throttlePIDAttenuation;
uint16_t filteredCycleTime; uint16_t filteredCycleTime;
bool isRXDataNew; bool isRXDataNew;
static bool armingCalibrationWasInitialised; static bool armingCalibrationWasInitialised;
float setpointRate[3]; static float setpointRate[3];
float rcInput[3]; static float rcDeflection[3];
float getThrottlePIDAttenuation(void) {
return throttlePIDAttenuation;
}
float getSetpointRate(int axis) {
return setpointRate[axis];
}
float getRcDeflection(int axis) {
return rcDeflection[axis];
}
void applyAndSaveAccelerometerTrimsDelta(rollAndPitchTrims_t *rollAndPitchTrimsDelta) void applyAndSaveAccelerometerTrimsDelta(rollAndPitchTrims_t *rollAndPitchTrimsDelta)
{ {
@ -109,30 +120,6 @@ void applyAndSaveAccelerometerTrimsDelta(rollAndPitchTrims_t *rollAndPitchTrimsD
saveConfigAndNotify(); saveConfigAndNotify();
} }
#ifdef GTUNE
void updateGtuneState(void)
{
static bool GTuneWasUsed = false;
if (IS_RC_MODE_ACTIVE(BOXGTUNE)) {
if (!FLIGHT_MODE(GTUNE_MODE) && ARMING_FLAG(ARMED)) {
ENABLE_FLIGHT_MODE(GTUNE_MODE);
init_Gtune(&currentProfile->pidProfile);
GTuneWasUsed = true;
}
if (!FLIGHT_MODE(GTUNE_MODE) && !ARMING_FLAG(ARMED) && GTuneWasUsed) {
saveConfigAndNotify();
GTuneWasUsed = false;
}
} else {
if (FLIGHT_MODE(GTUNE_MODE) && ARMING_FLAG(ARMED)) {
DISABLE_FLIGHT_MODE(GTUNE_MODE);
}
}
}
#endif
bool isCalibrating() bool isCalibrating()
{ {
#ifdef BARO #ifdef BARO
@ -162,11 +149,11 @@ void calculateSetpointRate(int axis, int16_t rc) {
if (rcRate > 2.0f) rcRate = rcRate + (RC_RATE_INCREMENTAL * (rcRate - 2.0f)); if (rcRate > 2.0f) rcRate = rcRate + (RC_RATE_INCREMENTAL * (rcRate - 2.0f));
rcCommandf = rc / 500.0f; rcCommandf = rc / 500.0f;
rcInput[axis] = ABS(rcCommandf); rcDeflection[axis] = ABS(rcCommandf);
if (rcExpo) { if (rcExpo) {
float expof = rcExpo / 100.0f; float expof = rcExpo / 100.0f;
rcCommandf = rcCommandf * power3(rcInput[axis]) * expof + rcCommandf * (1-expof); rcCommandf = rcCommandf * power3(rcDeflection[axis]) * expof + rcCommandf * (1-expof);
} }
angleRate = 200.0f * rcRate * rcCommandf; angleRate = 200.0f * rcRate * rcCommandf;
@ -199,20 +186,45 @@ void scaleRcCommandToFpvCamAngle(void) {
rcCommand[YAW] = constrain(yaw * cosFactor + roll * sinFactor, -500, 500); rcCommand[YAW] = constrain(yaw * cosFactor + roll * sinFactor, -500, 500);
} }
#define THROTTLE_BUFFER_MAX 20
#define THROTTLE_DELTA_MS 100
void checkForThrottleErrorResetState(uint16_t rxRefreshRate) {
static int index;
static int16_t rcCommandThrottlePrevious[THROTTLE_BUFFER_MAX];
const int rxRefreshRateMs = rxRefreshRate / 1000;
const int indexMax = constrain(THROTTLE_DELTA_MS / rxRefreshRateMs, 1, THROTTLE_BUFFER_MAX);
const int16_t throttleVelocityThreshold = (feature(FEATURE_3D)) ? currentProfile->pidProfile.itermThrottleThreshold / 2 : currentProfile->pidProfile.itermThrottleThreshold;
rcCommandThrottlePrevious[index++] = rcCommand[THROTTLE];
if (index >= indexMax)
index = 0;
const int16_t rcCommandSpeed = rcCommand[THROTTLE] - rcCommandThrottlePrevious[index];
if(ABS(rcCommandSpeed) > throttleVelocityThreshold)
pidResetErrorGyroState();
}
void processRcCommand(void) void processRcCommand(void)
{ {
static int16_t lastCommand[4] = { 0, 0, 0, 0 }; static int16_t lastCommand[4] = { 0, 0, 0, 0 };
static int16_t deltaRC[4] = { 0, 0, 0, 0 }; static int16_t deltaRC[4] = { 0, 0, 0, 0 };
static int16_t factor, rcInterpolationFactor; static int16_t factor, rcInterpolationFactor;
static uint16_t currentRxRefreshRate;
uint16_t rxRefreshRate; uint16_t rxRefreshRate;
bool readyToCalculateRate = false; bool readyToCalculateRate = false;
if (isRXDataNew) {
currentRxRefreshRate = constrain(getTaskDeltaTime(TASK_RX),1000,20000);
checkForThrottleErrorResetState(currentRxRefreshRate);
}
if (rxConfig()->rcInterpolation || flightModeFlags) { if (rxConfig()->rcInterpolation || flightModeFlags) {
if (isRXDataNew) { // Set RC refresh rate for sampling and channels to filter
// Set RC refresh rate for sampling and channels to filter switch(rxConfig()->rcInterpolation) {
switch (rxConfig()->rcInterpolation) {
case(RC_SMOOTHING_AUTO): case(RC_SMOOTHING_AUTO):
rxRefreshRate = constrain(getTaskDeltaTime(TASK_RX), 1000, 20000) + 1000; // Add slight overhead to prevent ramps rxRefreshRate = currentRxRefreshRate + 1000; // Add slight overhead to prevent ramps
break; break;
case(RC_SMOOTHING_MANUAL): case(RC_SMOOTHING_MANUAL):
rxRefreshRate = 1000 * rxConfig()->rcInterpolationInterval; rxRefreshRate = 1000 * rxConfig()->rcInterpolationInterval;
@ -221,8 +233,9 @@ void processRcCommand(void)
case(RC_SMOOTHING_DEFAULT): case(RC_SMOOTHING_DEFAULT):
default: default:
rxRefreshRate = rxGetRefreshRate(); rxRefreshRate = rxGetRefreshRate();
} }
if (isRXDataNew) {
rcInterpolationFactor = rxRefreshRate / targetPidLooptime + 1; rcInterpolationFactor = rxRefreshRate / targetPidLooptime + 1;
if (debugMode == DEBUG_RC_INTERPOLATION) { if (debugMode == DEBUG_RC_INTERPOLATION) {
@ -269,17 +282,18 @@ void updateRcCommands(void)
int32_t prop; int32_t prop;
if (rcData[THROTTLE] < currentControlRateProfile->tpa_breakpoint) { if (rcData[THROTTLE] < currentControlRateProfile->tpa_breakpoint) {
prop = 100; prop = 100;
throttlePIDAttenuation = 1.0f;
} else { } else {
if (rcData[THROTTLE] < 2000) { if (rcData[THROTTLE] < 2000) {
prop = 100 - (uint16_t)currentControlRateProfile->dynThrPID * (rcData[THROTTLE] - currentControlRateProfile->tpa_breakpoint) / (2000 - currentControlRateProfile->tpa_breakpoint); prop = 100 - (uint16_t)currentControlRateProfile->dynThrPID * (rcData[THROTTLE] - currentControlRateProfile->tpa_breakpoint) / (2000 - currentControlRateProfile->tpa_breakpoint);
} else { } else {
prop = 100 - currentControlRateProfile->dynThrPID; prop = 100 - currentControlRateProfile->dynThrPID;
} }
throttlePIDAttenuation = prop / 100.0f;
} }
for (int axis = 0; axis < 3; axis++) { for (int axis = 0; axis < 3; axis++) {
// non coupled PID reduction scaler used in PID controller 1 and PID controller 2. // non coupled PID reduction scaler used in PID controller 1 and PID controller 2.
PIDweight[axis] = prop;
int32_t tmp = MIN(ABS(rcData[axis] - rxConfig()->midrc), 500); int32_t tmp = MIN(ABS(rcData[axis] - rxConfig()->midrc), 500);
if (axis == ROLL || axis == PITCH) { if (axis == ROLL || axis == PITCH) {
@ -678,9 +692,7 @@ void subTaskPidController(void)
// PID - note this is function pointer set by setPIDController() // PID - note this is function pointer set by setPIDController()
pidController( pidController(
&currentProfile->pidProfile, &currentProfile->pidProfile,
pidConfig()->max_angle_inclination, &accelerometerConfig()->accelerometerTrims
&accelerometerConfig()->accelerometerTrims,
rxConfig()->midrc
); );
if (debugMode == DEBUG_PIDLOOP || debugMode == DEBUG_SCHEDULER) {debug[1] = micros() - startTime;} if (debugMode == DEBUG_PIDLOOP || debugMode == DEBUG_SCHEDULER) {debug[1] = micros() - startTime;}
} }

View File

@ -34,3 +34,6 @@ void updateLEDs(void);
void updateRcCommands(void); void updateRcCommands(void);
void taskMainPidLoop(timeUs_t currentTimeUs); void taskMainPidLoop(timeUs_t currentTimeUs);
float getThrottlePIDAttenuation(void);
float getSetpointRate(int axis);
float getRcDeflection(int axis);

View File

@ -49,7 +49,7 @@
#include "drivers/serial_escserial.h" #include "drivers/serial_escserial.h"
#include "fc/config.h" #include "fc/config.h"
#include "fc/mw.h" #include "fc/fc_main.h"
#include "fc/fc_msp.h" #include "fc/fc_msp.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "fc/runtime_config.h" #include "fc/runtime_config.h"
@ -401,10 +401,6 @@ void initActiveBoxIds(void)
} }
#endif #endif
#ifdef GTUNE
activeBoxIds[activeBoxIdCount++] = BOXGTUNE;
#endif
#ifdef USE_SERVOS #ifdef USE_SERVOS
if (mixerConfig()->mixerMode == MIXER_CUSTOM_AIRPLANE) { if (mixerConfig()->mixerMode == MIXER_CUSTOM_AIRPLANE) {
activeBoxIds[activeBoxIdCount++] = BOXSERVO1; activeBoxIds[activeBoxIdCount++] = BOXSERVO1;
@ -1167,9 +1163,9 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
sbufWriteU8(dst, currentProfile->pidProfile.dtermSetpointWeight); sbufWriteU8(dst, currentProfile->pidProfile.dtermSetpointWeight);
sbufWriteU8(dst, 0); // reserved sbufWriteU8(dst, 0); // reserved
sbufWriteU8(dst, 0); // reserved sbufWriteU8(dst, 0); // reserved
sbufWriteU8(dst, currentProfile->pidProfile.itermThrottleGain); sbufWriteU8(dst, 0); // reserved
sbufWriteU16(dst, currentProfile->pidProfile.rateAccelLimit); sbufWriteU16(dst, currentProfile->pidProfile.rateAccelLimit * 10);
sbufWriteU16(dst, currentProfile->pidProfile.yawRateAccelLimit); sbufWriteU16(dst, currentProfile->pidProfile.yawRateAccelLimit * 10);
break; break;
case MSP_SENSOR_CONFIG: case MSP_SENSOR_CONFIG:
@ -1515,9 +1511,9 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
currentProfile->pidProfile.dtermSetpointWeight = sbufReadU8(src); currentProfile->pidProfile.dtermSetpointWeight = sbufReadU8(src);
sbufReadU8(src); // reserved sbufReadU8(src); // reserved
sbufReadU8(src); // reserved sbufReadU8(src); // reserved
currentProfile->pidProfile.itermThrottleGain = sbufReadU8(src); sbufReadU8(src); // reserved
currentProfile->pidProfile.rateAccelLimit = sbufReadU16(src); currentProfile->pidProfile.rateAccelLimit = sbufReadU16(src) / 10.0f;
currentProfile->pidProfile.yawRateAccelLimit = sbufReadU16(src); currentProfile->pidProfile.yawRateAccelLimit = sbufReadU16(src) / 10.0f;
pidInitConfig(&currentProfile->pidProfile); pidInitConfig(&currentProfile->pidProfile);
break; break;

View File

@ -36,7 +36,7 @@
#include "fc/config.h" #include "fc/config.h"
#include "fc/fc_msp.h" #include "fc/fc_msp.h"
#include "fc/fc_tasks.h" #include "fc/fc_tasks.h"
#include "fc/mw.h" #include "fc/fc_main.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "fc/runtime_config.h" #include "fc/runtime_config.h"

View File

@ -35,7 +35,7 @@
#include "drivers/system.h" #include "drivers/system.h"
#include "fc/config.h" #include "fc/config.h"
#include "fc/mw.h" #include "fc/fc_main.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "fc/rc_curves.h" #include "fc/rc_curves.h"
#include "fc/runtime_config.h" #include "fc/runtime_config.h"

View File

@ -42,8 +42,7 @@ typedef enum {
UNUSED_MODE = (1 << 7), // old autotune UNUSED_MODE = (1 << 7), // old autotune
PASSTHRU_MODE = (1 << 8), PASSTHRU_MODE = (1 << 8),
SONAR_MODE = (1 << 9), SONAR_MODE = (1 << 9),
FAILSAFE_MODE = (1 << 10), FAILSAFE_MODE = (1 << 10)
GTUNE_MODE = (1 << 11)
} flightModeFlags_e; } flightModeFlags_e;
extern uint16_t flightModeFlags; extern uint16_t flightModeFlags;

View File

@ -1,211 +0,0 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include <math.h>
#include "platform.h"
#ifdef GTUNE
#include "common/axis.h"
#include "common/maths.h"
#include "drivers/system.h"
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "sensors/sensors.h"
#include "sensors/gyro.h"
#include "sensors/acceleration.h"
#include "flight/pid.h"
#include "flight/imu.h"
#include "blackbox/blackbox.h"
#include "fc/config.h"
#include "fc/rc_controls.h"
#include "fc/runtime_config.h"
extern uint16_t cycleTime;
extern uint8_t motorCount;
/*
****************************************************************************
*** G_Tune ***
****************************************************************************
G_Tune Mode
This is the multiwii implementation of ZERO-PID Algorithm
http://technicaladventure.blogspot.com/2014/06/zero-pids-tuner-for-multirotors.html
The algorithm has been originally developed by Mohammad Hefny (mohammad.hefny@gmail.com)
You may use/modify this algorithm on your own risk, kindly refer to above link in any future distribution.
*/
/*
version 1.0.0: MIN & Maxis & Tuned Band
version 1.0.1:
a. error is gyro reading not rc - gyro.
b. OldError = Error no averaging.
c. No Min Maxis BOUNDRY
version 1.0.2:
a. no boundaries
b. I - Factor tune.
c. time_skip
Crashpilot: Reduced to just P tuning in a predefined range - so it is not "zero pid" anymore.
Tuning is limited to just work when stick is centered besides that YAW is tuned in non Acro as well.
See also:
http://diydrones.com/profiles/blogs/zero-pid-tunes-for-multirotors-part-2
http://www.multiwii.com/forum/viewtopic.php?f=8&t=5190
Gyrosetting 2000DPS
GyroScale = (1 / 16,4 ) * RADX(see board.h) = 0,001064225154 digit per rad/s
pidProfile->gtune_lolimP[ROLL] = 10; [0..200] Lower limit of ROLL P during G tune.
pidProfile->gtune_lolimP[PITCH] = 10; [0..200] Lower limit of PITCH P during G tune.
pidProfile->gtune_lolimP[YAW] = 10; [0..200] Lower limit of YAW P during G tune.
pidProfile->gtune_hilimP[ROLL] = 100; [0..200] Higher limit of ROLL P during G tune. 0 Disables tuning for that axisis.
pidProfile->gtune_hilimP[PITCH] = 100; [0..200] Higher limit of PITCH P during G tune. 0 Disables tuning for that axisis.
pidProfile->gtune_hilimP[YAW] = 100; [0..200] Higher limit of YAW P during G tune. 0 Disables tuning for that axisis.
pidProfile->gtune_pwr = 0; [0..10] Strength of adjustment
pidProfile->gtune_settle_time = 450; [200..1000] Settle time in ms
pidProfile->gtune_average_cycles = 16; [8..128] Number of looptime cycles used for gyro average calculation
*/
static pidProfile_t *pidProfile;
static int16_t delay_cycles;
static int16_t time_skip[3];
static int16_t OldError[3], result_P64[3];
static int32_t AvgGyro[3];
static bool floatPID;
void updateDelayCycles(void)
{
delay_cycles = -(((int32_t)pidProfile->gtune_settle_time * 1000) / cycleTime);
}
void init_Gtune(pidProfile_t *pidProfileToTune)
{
uint8_t i;
pidProfile = pidProfileToTune;
if (pidProfile->pidController == 2) {
floatPID = true; // LuxFloat is using float values for PID settings
} else {
floatPID = false;
}
updateDelayCycles();
for (i = 0; i < 3; i++) {
if ((pidProfile->gtune_hilimP[i] && pidProfile->gtune_lolimP[i] > pidProfile->gtune_hilimP[i]) || (motorCount < 4 && i == FD_YAW)) { // User config error disable axisis for tuning
pidProfile->gtune_hilimP[i] = 0; // Disable YAW tuning for everything below a quadcopter
}
if (floatPID) {
if((pidProfile->P_f[i] * 10.0f) < pidProfile->gtune_lolimP[i]) {
pidProfile->P_f[i] = (float)(pidProfile->gtune_lolimP[i] / 10.0f);
}
result_P64[i] = (int16_t)pidProfile->P_f[i] << 6; // 6 bit extra resolution for P.
} else {
if(pidProfile->P8[i] < pidProfile->gtune_lolimP[i]) {
pidProfile->P8[i] = pidProfile->gtune_lolimP[i];
}
result_P64[i] = (int16_t)pidProfile->P8[i] << 6; // 6 bit extra resolution for P.
}
OldError[i] = 0;
time_skip[i] = delay_cycles;
}
}
void calculate_Gtune(uint8_t axis)
{
int16_t error, diff_G, threshP;
if(rcCommand[axis] || (axis != FD_YAW && (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)))) { // Block tuning on stick input. Always allow G-Tune on YAW, Roll & Pitch only in acromode
OldError[axis] = 0;
time_skip[axis] = delay_cycles; // Some settle time after stick center. default 450ms
} else {
if (!time_skip[axis]) AvgGyro[axis] = 0;
time_skip[axis]++;
if (time_skip[axis] > 0) {
if (axis == FD_YAW) {
AvgGyro[axis] += 32 * ((int16_t)gyroADC[axis] / 32); // Chop some jitter and average
} else {
AvgGyro[axis] += 128 * ((int16_t)gyroADC[axis] / 128); // Chop some jitter and average
}
}
if (time_skip[axis] == pidProfile->gtune_average_cycles) { // Looptime cycles for gyro average calculation. default 16.
AvgGyro[axis] /= time_skip[axis]; // AvgGyro[axis] has now very clean gyrodata
time_skip[axis] = 0;
if (axis == FD_YAW) {
threshP = 20;
error = -AvgGyro[axis];
} else {
threshP = 10;
error = AvgGyro[axis];
}
if (pidProfile->gtune_hilimP[axis] && error && OldError[axis] && error != OldError[axis]) { // Don't run when not needed or pointless to do so
diff_G = ABS(error) - ABS(OldError[axis]);
if ((error > 0 && OldError[axis] > 0) || (error < 0 && OldError[axis] < 0)) {
if (diff_G > threshP) {
if (axis == FD_YAW) {
result_P64[axis] += 256 + pidProfile->gtune_pwr; // YAW ends up at low limit on float PID, give it some more to work with.
} else {
result_P64[axis] += 64 + pidProfile->gtune_pwr; // Shift balance a little on the plus side.
}
} else {
if (diff_G < -threshP) {
if (axis == FD_YAW) {
result_P64[axis] -= 64 + pidProfile->gtune_pwr;
} else {
result_P64[axis] -= 32;
}
}
}
} else {
if (ABS(diff_G) > threshP && axis != FD_YAW) {
result_P64[axis] -= 32; // Don't use antiwobble for YAW
}
}
int16_t newP = constrain((result_P64[axis] >> 6), (int16_t)pidProfile->gtune_lolimP[axis], (int16_t)pidProfile->gtune_hilimP[axis]);
#ifdef BLACKBOX
if (feature(FEATURE_BLACKBOX)) {
flightLogEvent_gtuneCycleResult_t eventData;
eventData.gtuneAxis = axis;
eventData.gtuneGyroAVG = AvgGyro[axis];
eventData.gtuneNewP = newP; // for float PID the logged P value is still mutiplyed by 10
blackboxLogEvent(FLIGHT_LOG_EVENT_GTUNE_RESULT, (flightLogEventData_t*)&eventData);
}
#endif
if (floatPID) {
pidProfile->P_f[axis] = (float)newP / 10.0f; // new P value for float PID
} else {
pidProfile->P8[axis] = newP; // new P value
}
}
OldError[axis] = error;
}
}
}
#endif

View File

@ -1,21 +0,0 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
void init_Gtune(pidProfile_t *pidProfileToTune);
void calculate_Gtune(uint8_t axis);

View File

@ -534,19 +534,6 @@ void mixTable(pidProfile_t *pidProfile)
} }
} }
// Anti Desync feature for ESC's. Limit rapid throttle changes
if (motorConfig->maxEscThrottleJumpMs) {
const int16_t maxThrottleStep = constrain(motorConfig->maxEscThrottleJumpMs / (1000 / targetPidLooptime), 2, 10000);
// Only makes sense when it's within the range
if (maxThrottleStep < motorOutputRange) {
static int16_t motorPrevious[MAX_SUPPORTED_MOTORS];
motor[i] = constrain(motor[i], motorOutputMin, motorPrevious[i] + maxThrottleStep); // Only limit accelerating situation
motorPrevious[i] = motor[i];
}
}
// Disarmed mode // Disarmed mode
if (!ARMING_FLAG(ARMED)) { if (!ARMING_FLAG(ARMED)) {
for (i = 0; i < motorCount; i++) { for (i = 0; i < motorCount; i++) {

View File

@ -28,28 +28,22 @@
#include "common/maths.h" #include "common/maths.h"
#include "common/filter.h" #include "common/filter.h"
#include "fc/fc_main.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "fc/runtime_config.h" #include "fc/runtime_config.h"
#include "flight/pid.h" #include "flight/pid.h"
#include "flight/imu.h" #include "flight/imu.h"
#include "flight/navigation.h" #include "flight/navigation.h"
#include "flight/gtune.h"
#include "sensors/gyro.h" #include "sensors/gyro.h"
#include "sensors/acceleration.h" #include "sensors/acceleration.h"
extern float rcInput[3];
extern float setpointRate[3];
uint32_t targetPidLooptime; uint32_t targetPidLooptime;
static bool pidStabilisationEnabled; static bool pidStabilisationEnabled;
float axisPIDf[3]; float axisPIDf[3];
// PIDweight is a scale factor for PIDs which is derived from the throttle and TPA setting, and 100 = 100% scale means no PID reduction
uint8_t PIDweight[3];
#ifdef BLACKBOX #ifdef BLACKBOX
int32_t axisPID_P[3], axisPID_I[3], axisPID_D[3]; int32_t axisPID_P[3], axisPID_I[3], axisPID_D[3];
#endif #endif
@ -146,8 +140,7 @@ void pidInitFilters(const pidProfile_t *pidProfile)
} }
} }
static float Kp[3], Ki[3], Kd[3], c[3]; static float Kp[3], Ki[3], Kd[3], c[3], levelGain, horizonGain, horizonTransition, maxVelocity[3], relaxFactor[3];
static float rollPitchMaxVelocity, yawMaxVelocity, relaxFactor[3];
void pidInitConfig(const pidProfile_t *pidProfile) { void pidInitConfig(const pidProfile_t *pidProfile) {
for(int axis = FD_ROLL; axis <= FD_YAW; axis++) { for(int axis = FD_ROLL; axis <= FD_YAW; axis++) {
@ -157,88 +150,85 @@ void pidInitConfig(const pidProfile_t *pidProfile) {
c[axis] = pidProfile->dtermSetpointWeight / 100.0f; c[axis] = pidProfile->dtermSetpointWeight / 100.0f;
relaxFactor[axis] = 1.0f - (pidProfile->setpointRelaxRatio / 100.0f); relaxFactor[axis] = 1.0f - (pidProfile->setpointRelaxRatio / 100.0f);
} }
yawMaxVelocity = pidProfile->yawRateAccelLimit * 1000 * dT; levelGain = pidProfile->P8[PIDLEVEL] / 10.0f;
rollPitchMaxVelocity = pidProfile->rateAccelLimit * 1000 * dT; horizonGain = pidProfile->I8[PIDLEVEL] / 10.0f;
horizonTransition = 100.0f / pidProfile->D8[PIDLEVEL];
maxVelocity[FD_ROLL] = maxVelocity[FD_PITCH] = pidProfile->rateAccelLimit * 1000 * dT;
maxVelocity[FD_YAW] = pidProfile->yawRateAccelLimit * 1000 * dT;
}
float currentPidSetpoint = 0, horizonLevelStrength = 1.0f;
void calcHorizonLevelStrength(const pidProfile_t *pidProfile) {
const float mostDeflectedPos = MAX(getRcDeflection(FD_ROLL), getRcDeflection(FD_PITCH));
// Progressively turn off the horizon self level strength as the stick is banged over
horizonLevelStrength = (1.0f - mostDeflectedPos); // 1 at centre stick, 0 = max stick deflection
if(pidProfile->D8[PIDLEVEL] == 0){
horizonLevelStrength = 0;
} else {
horizonLevelStrength = constrainf(((horizonLevelStrength - 1) * horizonTransition) + 1, 0, 1);
}
}
void pidLevel(int axis, const pidProfile_t *pidProfile, const rollAndPitchTrims_t *angleTrim) {
// calculate error angle and limit the angle to the max inclination
float errorAngle = pidProfile->levelSensitivity * rcCommand[axis];
#ifdef GPS
errorAngle += GPS_angle[axis];
#endif
errorAngle = constrainf(errorAngle, -pidProfile->max_angle_inclination, pidProfile->max_angle_inclination);
errorAngle = (errorAngle - ((attitude.raw[axis] + angleTrim->raw[axis]) / 10.0f));
if(FLIGHT_MODE(ANGLE_MODE)) {
// ANGLE mode - control is angle based, so control loop is needed
currentPidSetpoint = errorAngle * levelGain;
} else {
// HORIZON mode - direct sticks control is applied to rate PID
// mix up angle error to desired AngleRate to add a little auto-level feel
currentPidSetpoint = currentPidSetpoint + (errorAngle * horizonGain * horizonLevelStrength);
}
}
void accelerationLimit(int axis) {
static float previousSetpoint[3];
const float currentVelocity = currentPidSetpoint- previousSetpoint[axis];
if(ABS(currentVelocity) > maxVelocity[axis])
currentPidSetpoint = (currentVelocity > 0) ? previousSetpoint[axis] + maxVelocity[axis] : previousSetpoint[axis] - maxVelocity[axis];
previousSetpoint[axis] = currentPidSetpoint;
} }
// Betaflight pid controller, which will be maintained in the future with additional features specialised for current (mini) multirotor usage. // Betaflight pid controller, which will be maintained in the future with additional features specialised for current (mini) multirotor usage.
// Based on 2DOF reference design (matlab) // Based on 2DOF reference design (matlab)
void pidController(const pidProfile_t *pidProfile, uint16_t max_angle_inclination, const rollAndPitchTrims_t *angleTrim, uint16_t midrc) void pidController(const pidProfile_t *pidProfile, const rollAndPitchTrims_t *angleTrim)
{ {
static float previousRateError[2]; static float previousRateError[2];
static float previousSetpoint[3]; static float previousSetpoint[3];
float horizonLevelStrength = 1; if(FLIGHT_MODE(HORIZON_MODE))
if (FLIGHT_MODE(HORIZON_MODE)) { calcHorizonLevelStrength(pidProfile);
// Figure out the raw stick positions
const int32_t stickPosAil = ABS(getRcStickDeflection(FD_ROLL, midrc));
const int32_t stickPosEle = ABS(getRcStickDeflection(FD_PITCH, midrc));
const int32_t mostDeflectedPos = MAX(stickPosAil, stickPosEle);
// Progressively turn off the horizon self level strength as the stick is banged over
horizonLevelStrength = (float)(500 - mostDeflectedPos) / 500; // 1 at centre stick, 0 = max stick deflection
if(pidProfile->D8[PIDLEVEL] == 0){
horizonLevelStrength = 0;
} else {
horizonLevelStrength = constrainf(((horizonLevelStrength - 1) * (100 / pidProfile->D8[PIDLEVEL])) + 1, 0, 1);
}
}
// Yet Highly experimental and under test and development
// Throttle coupled to Igain like inverted TPA // 50hz calculation (should cover all rx protocols)
static float kiThrottleGain = 1.0f;
if (pidProfile->itermThrottleGain) {
const uint16_t maxLoopCount = 20000 / targetPidLooptime;
const float throttleItermGain = (float)pidProfile->itermThrottleGain * 0.001f;
static int16_t previousThrottle;
static uint16_t loopIncrement;
if (loopIncrement >= maxLoopCount) {
kiThrottleGain = 1.0f + constrainf((float)(ABS(rcCommand[THROTTLE] - previousThrottle)) * throttleItermGain, 0.0f, 5.0f); // Limit to factor 5
previousThrottle = rcCommand[THROTTLE];
loopIncrement = 0;
} else {
loopIncrement++;
}
}
// ----------PID controller---------- // ----------PID controller----------
const float tpaFactor = PIDweight[0] / 100.0f; // tpa is now float const float tpaFactor = getThrottlePIDAttenuation();
for (int axis = FD_ROLL; axis <= FD_YAW; axis++) { for (int axis = FD_ROLL; axis <= FD_YAW; axis++) {
// Limit abrupt yaw inputs / stops currentPidSetpoint = getSetpointRate(axis);
const float maxVelocity = (axis == FD_YAW) ? yawMaxVelocity : rollPitchMaxVelocity;
if (maxVelocity) { if(maxVelocity[axis])
const float currentVelocity = setpointRate[axis] - previousSetpoint[axis]; accelerationLimit(axis);
if (ABS(currentVelocity) > maxVelocity) {
setpointRate[axis] = (currentVelocity > 0) ? previousSetpoint[axis] + maxVelocity : previousSetpoint[axis] - maxVelocity;
}
}
// Yaw control is GYRO based, direct sticks control is applied to rate PID // Yaw control is GYRO based, direct sticks control is applied to rate PID
if ((FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) && axis != YAW) { if ((FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) && axis != YAW) {
// calculate error angle and limit the angle to the max inclination pidLevel(axis, pidProfile, angleTrim);
float errorAngle = pidProfile->levelSensitivity * rcCommand[axis];
#ifdef GPS
errorAngle += GPS_angle[axis];
#endif
errorAngle = constrainf(errorAngle, -max_angle_inclination, max_angle_inclination);
errorAngle = (errorAngle - attitude.raw[axis] + angleTrim->raw[axis]) / 10.0f;
if (FLIGHT_MODE(ANGLE_MODE)) {
// ANGLE mode - control is angle based, so control loop is needed
setpointRate[axis] = errorAngle * pidProfile->P8[PIDLEVEL] / 10.0f;
} else {
// HORIZON mode - direct sticks control is applied to rate PID
// mix up angle error to desired AngleRate to add a little auto-level feel
setpointRate[axis] = setpointRate[axis] + (errorAngle * pidProfile->I8[PIDLEVEL] * horizonLevelStrength / 10.0f);
}
} }
const float PVRate = gyro.gyroADCf[axis]; // Process variable from gyro output in deg/sec const float gyroRate = gyro.gyroADCf[axis]; // Process variable from gyro output in deg/sec
// --------low-level gyro-based PID based on 2DOF PID controller. ---------- // --------low-level gyro-based PID based on 2DOF PID controller. ----------
// ---------- 2-DOF PID controller with optional filter on derivative term. b = 1 and only c can be tuned (amount derivative on measurement or error). ---------- // ---------- 2-DOF PID controller with optional filter on derivative term. b = 1 and only c can be tuned (amount derivative on measurement or error). ----------
// -----calculate error rate // -----calculate error rate
const float errorRate = setpointRate[axis] - PVRate; // r - y const float errorRate = currentPidSetpoint - gyroRate; // r - y
// -----calculate P component and add Dynamic Part based on stick input // -----calculate P component and add Dynamic Part based on stick input
float PTerm = Kp[axis] * errorRate * tpaFactor; float PTerm = Kp[axis] * errorRate * tpaFactor;
@ -246,11 +236,10 @@ void pidController(const pidProfile_t *pidProfile, uint16_t max_angle_inclinatio
// -----calculate I component // -----calculate I component
// Reduce strong Iterm accumulation during higher stick inputs // Reduce strong Iterm accumulation during higher stick inputs
const float accumulationThreshold = (axis == FD_YAW) ? pidProfile->yawItermIgnoreRate : pidProfile->rollPitchItermIgnoreRate; const float accumulationThreshold = (axis == FD_YAW) ? pidProfile->yawItermIgnoreRate : pidProfile->rollPitchItermIgnoreRate;
const float setpointRateScaler = constrainf(1.0f - (ABS(setpointRate[axis]) / accumulationThreshold), 0.0f, 1.0f); const float setpointRateScaler = constrainf(1.0f - (ABS(currentPidSetpoint) / accumulationThreshold), 0.0f, 1.0f);
const float itermScaler = setpointRateScaler * kiThrottleGain;
float ITerm = previousGyroIf[axis]; float ITerm = previousGyroIf[axis];
ITerm += Ki[axis] * errorRate * dT * itermScaler;; ITerm += Ki[axis] * errorRate * dT * setpointRateScaler;
// limit maximum integrator value to prevent WindUp // limit maximum integrator value to prevent WindUp
ITerm = constrainf(ITerm, -250.0f, 250.0f); ITerm = constrainf(ITerm, -250.0f, 250.0f);
previousGyroIf[axis] = ITerm; previousGyroIf[axis] = ITerm;
@ -260,16 +249,17 @@ void pidController(const pidProfile_t *pidProfile, uint16_t max_angle_inclinatio
if (axis != FD_YAW) { if (axis != FD_YAW) {
float dynC = c[axis]; float dynC = c[axis];
if (pidProfile->setpointRelaxRatio < 100) { if (pidProfile->setpointRelaxRatio < 100) {
const float rcDeflection = getRcDeflection(axis);
dynC = c[axis]; dynC = c[axis];
if (setpointRate[axis] > 0) { if (currentPidSetpoint > 0) {
if ((setpointRate[axis] - previousSetpoint[axis]) < previousSetpoint[axis]) if ((currentPidSetpoint - previousSetpoint[axis]) < previousSetpoint[axis])
dynC = dynC * sq(rcInput[axis]) * relaxFactor[axis] + dynC * (1-relaxFactor[axis]); dynC = dynC * sq(rcDeflection) * relaxFactor[axis] + dynC * (1-relaxFactor[axis]);
} else if (setpointRate[axis] < 0) { } else if (currentPidSetpoint < 0) {
if ((setpointRate[axis] - previousSetpoint[axis]) > previousSetpoint[axis]) if ((currentPidSetpoint - previousSetpoint[axis]) > previousSetpoint[axis])
dynC = dynC * sq(rcInput[axis]) * relaxFactor[axis] + dynC * (1-relaxFactor[axis]); dynC = dynC * sq(rcDeflection) * relaxFactor[axis] + dynC * (1-relaxFactor[axis]);
} }
} }
const float rD = dynC * setpointRate[axis] - PVRate; // cr - y const float rD = dynC * currentPidSetpoint - gyroRate; // cr - y
// Divide rate change by dT to get differential (ie dr/dt) // Divide rate change by dT to get differential (ie dr/dt)
const float delta = (rD - previousRateError[axis]) / dT; const float delta = (rD - previousRateError[axis]) / dT;
previousRateError[axis] = rD; previousRateError[axis] = rD;
@ -284,19 +274,13 @@ void pidController(const pidProfile_t *pidProfile, uint16_t max_angle_inclinatio
} else { } else {
PTerm = ptermYawFilterApplyFn(ptermYawFilter, PTerm); PTerm = ptermYawFilterApplyFn(ptermYawFilter, PTerm);
} }
previousSetpoint[axis] = setpointRate[axis]; previousSetpoint[axis] = currentPidSetpoint;
// -----calculate total PID output // -----calculate total PID output
axisPIDf[axis] = PTerm + ITerm + DTerm; axisPIDf[axis] = PTerm + ITerm + DTerm;
// Disable PID control at zero throttle // Disable PID control at zero throttle
if (!pidStabilisationEnabled) axisPIDf[axis] = 0; if (!pidStabilisationEnabled) axisPIDf[axis] = 0;
#ifdef GTUNE
if (FLIGHT_MODE(GTUNE_MODE) && ARMING_FLAG(ARMED)) {
calculate_Gtune(axis);
}
#endif
#ifdef BLACKBOX #ifdef BLACKBOX
axisPID_P[axis] = PTerm; axisPID_P[axis] = PTerm;
axisPID_I[axis] = ITerm; axisPID_I[axis] = ITerm;

View File

@ -72,31 +72,23 @@ typedef struct pidProfile_s {
uint8_t dterm_average_count; // Configurable delta count for dterm uint8_t dterm_average_count; // Configurable delta count for dterm
uint8_t vbatPidCompensation; // Scale PIDsum to battery voltage uint8_t vbatPidCompensation; // Scale PIDsum to battery voltage
uint8_t pidAtMinThrottle; // Disable/Enable pids on zero throttle. Normally even without airmode P and D would be active. uint8_t pidAtMinThrottle; // Disable/Enable pids on zero throttle. Normally even without airmode P and D would be active.
float max_angle_inclination;
// Betaflight PID controller parameters // Betaflight PID controller parameters
uint8_t itermThrottleGain; // Throttle coupling to iterm. Quick throttle changes will bump iterm uint16_t itermThrottleThreshold; // max allowed throttle delta before errorGyroReset in ms
uint8_t setpointRelaxRatio; // Setpoint weight relaxation effect uint8_t setpointRelaxRatio; // Setpoint weight relaxation effect
uint8_t dtermSetpointWeight; // Setpoint weight for Dterm (0= measurement, 1= full error, 1 > agressive derivative) uint8_t dtermSetpointWeight; // Setpoint weight for Dterm (0= measurement, 1= full error, 1 > agressive derivative)
uint16_t yawRateAccelLimit; // yaw accel limiter for deg/sec/ms float yawRateAccelLimit; // yaw accel limiter for deg/sec/ms
uint16_t rateAccelLimit; // accel limiter roll/pitch deg/sec/ms float rateAccelLimit; // accel limiter roll/pitch deg/sec/ms
float levelSensitivity; float levelSensitivity;
#ifdef GTUNE
uint8_t gtune_lolimP[3]; // [0..200] Lower limit of P during G tune
uint8_t gtune_hilimP[3]; // [0..200] Higher limit of P during G tune. 0 Disables tuning for that axis.
uint8_t gtune_pwr; // [0..10] Strength of adjustment
uint16_t gtune_settle_time; // [200..1000] Settle time in ms
uint8_t gtune_average_cycles; // [8..128] Number of looptime cycles used for gyro average calculation
#endif
} pidProfile_t; } pidProfile_t;
typedef struct pidConfig_s { typedef struct pidConfig_s {
uint8_t pid_process_denom; // Processing denominator for PID controller vs gyro sampling rate uint8_t pid_process_denom; // Processing denominator for PID controller vs gyro sampling rate
uint16_t max_angle_inclination;
} pidConfig_t; } pidConfig_t;
union rollAndPitchTrims_u; union rollAndPitchTrims_u;
void pidController(const pidProfile_t *pidProfile, uint16_t max_angle_inclination, const union rollAndPitchTrims_u *angleTrim, uint16_t midrc); void pidController(const pidProfile_t *pidProfile, const union rollAndPitchTrims_u *angleTrim);
extern float axisPIDf[3]; extern float axisPIDf[3];
extern int32_t axisPID_P[3], axisPID_I[3], axisPID_D[3]; extern int32_t axisPID_P[3], axisPID_I[3], axisPID_D[3];

View File

@ -24,7 +24,6 @@ typedef struct motorConfig_s {
uint16_t minthrottle; // Set the minimum throttle command sent to the ESC (Electronic Speed Controller). This is the minimum value that allow motors to run at a idle speed. uint16_t minthrottle; // Set the minimum throttle command sent to the ESC (Electronic Speed Controller). This is the minimum value that allow motors to run at a idle speed.
uint16_t maxthrottle; // This is the maximum value for the ESCs at full power this value can be increased up to 2000 uint16_t maxthrottle; // This is the maximum value for the ESCs at full power this value can be increased up to 2000
uint16_t mincommand; // This is the value for the ESCs when they are not armed. In some cases, this value must be lowered down to 900 for some specific ESCs uint16_t mincommand; // This is the value for the ESCs when they are not armed. In some cases, this value must be lowered down to 900 for some specific ESCs
uint16_t maxEscThrottleJumpMs;
uint16_t motorPwmRate; // The update rate of motor outputs (50-498Hz) uint16_t motorPwmRate; // The update rate of motor outputs (50-498Hz)
uint8_t motorPwmProtocol; // Pwm Protocol uint8_t motorPwmProtocol; // Pwm Protocol
uint8_t useUnsyncedPwm; uint8_t useUnsyncedPwm;

View File

@ -715,8 +715,6 @@ const clivalue_t valueTable[] = {
#ifdef USE_DSHOT #ifdef USE_DSHOT
{ "digital_idle_percent", VAR_FLOAT | MASTER_VALUE, &motorConfig()->digitalIdleOffsetPercent, .config.minmax = { 0, 20} }, { "digital_idle_percent", VAR_FLOAT | MASTER_VALUE, &motorConfig()->digitalIdleOffsetPercent, .config.minmax = { 0, 20} },
#endif #endif
{ "max_esc_throttle_jump", VAR_UINT16 | MASTER_VALUE, &motorConfig()->maxEscThrottleJumpMs, .config.minmax = { 0, 1000 } },
{ "3d_deadband_low", VAR_UINT16 | MASTER_VALUE, &flight3DConfig()->deadband3d_low, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, // FIXME upper limit should match code in the mixer, 1500 currently { "3d_deadband_low", VAR_UINT16 | MASTER_VALUE, &flight3DConfig()->deadband3d_low, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, // FIXME upper limit should match code in the mixer, 1500 currently
{ "3d_deadband_high", VAR_UINT16 | MASTER_VALUE, &flight3DConfig()->deadband3d_high, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, // FIXME lower limit should match code in the mixer, 1500 currently, { "3d_deadband_high", VAR_UINT16 | MASTER_VALUE, &flight3DConfig()->deadband3d_high, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, // FIXME lower limit should match code in the mixer, 1500 currently,
{ "3d_neutral", VAR_UINT16 | MASTER_VALUE, &flight3DConfig()->neutral3d, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, { "3d_neutral", VAR_UINT16 | MASTER_VALUE, &flight3DConfig()->neutral3d, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
@ -757,18 +755,6 @@ const clivalue_t valueTable[] = {
{ "nav_slew_rate", VAR_UINT8 | MASTER_VALUE, &gpsProfile()->nav_slew_rate, .config.minmax = { 0, 100 } }, { "nav_slew_rate", VAR_UINT8 | MASTER_VALUE, &gpsProfile()->nav_slew_rate, .config.minmax = { 0, 100 } },
#endif #endif
#ifdef GTUNE
{ "gtune_loP_rll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_lolimP[FD_ROLL], .config.minmax = { 10, 200 } },
{ "gtune_loP_ptch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_lolimP[FD_PITCH], .config.minmax = { 10, 200 } },
{ "gtune_loP_yw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_lolimP[FD_YAW], .config.minmax = { 10, 200 } },
{ "gtune_hiP_rll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_hilimP[FD_ROLL], .config.minmax = { 0, 200 } },
{ "gtune_hiP_ptch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_hilimP[FD_PITCH], .config.minmax = { 0, 200 } },
{ "gtune_hiP_yw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_hilimP[FD_YAW], .config.minmax = { 0, 200 } },
{ "gtune_pwr", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_pwr, .config.minmax = { 0, 10 } },
{ "gtune_settle_time", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_settle_time, .config.minmax = { 200, 1000 } },
{ "gtune_average_cycles", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_average_cycles, .config.minmax = { 8, 128 } },
#endif
#ifdef BEEPER #ifdef BEEPER
{ "beeper_inversion", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &beeperConfig()->isInverted, .config.lookup = { TABLE_OFF_ON } }, { "beeper_inversion", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &beeperConfig()->isInverted, .config.lookup = { TABLE_OFF_ON } },
{ "beeper_od", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &beeperConfig()->isOpenDrain, .config.lookup = { TABLE_OFF_ON } }, { "beeper_od", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &beeperConfig()->isOpenDrain, .config.lookup = { TABLE_OFF_ON } },
@ -847,7 +833,7 @@ const clivalue_t valueTable[] = {
{ "yaw_motor_direction", VAR_INT8 | MASTER_VALUE, &mixerConfig()->yaw_motor_direction, .config.minmax = { -1, 1 } }, { "yaw_motor_direction", VAR_INT8 | MASTER_VALUE, &mixerConfig()->yaw_motor_direction, .config.minmax = { -1, 1 } },
{ "yaw_p_limit", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yaw_p_limit, .config.minmax = { YAW_P_LIMIT_MIN, YAW_P_LIMIT_MAX } }, { "yaw_p_limit", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yaw_p_limit, .config.minmax = { YAW_P_LIMIT_MIN, YAW_P_LIMIT_MAX } },
{ "pidsum_limit", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.pidSumLimit, .config.minmax = { 0.1, 1.0 } }, { "pidsum_limit", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.pidSumLimit, .config.minmax = { 0.1, 1.0 } },
{ "max_angle_inclination", VAR_UINT16 | MASTER_VALUE, &pidConfig()->max_angle_inclination, .config.minmax = { 100, 900 } }, { "max_angle_inclination", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.max_angle_inclination, .config.minmax = { 10.0f, 120.0f } },
#ifdef USE_SERVOS #ifdef USE_SERVOS
{ "servo_center_pulse", VAR_UINT16 | MASTER_VALUE, &servoConfig()->servoCenterPulse, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, { "servo_center_pulse", VAR_UINT16 | MASTER_VALUE, &servoConfig()->servoCenterPulse, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
{ "tri_unarmed_servo", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &servoMixerConfig()->tri_unarmed_servo, .config.lookup = { TABLE_OFF_ON } }, { "tri_unarmed_servo", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &servoMixerConfig()->tri_unarmed_servo, .config.lookup = { TABLE_OFF_ON } },
@ -906,11 +892,11 @@ const clivalue_t valueTable[] = {
{ "dterm_notch_cutoff", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.dterm_notch_cutoff, .config.minmax = { 1, 500 } }, { "dterm_notch_cutoff", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.dterm_notch_cutoff, .config.minmax = { 1, 500 } },
{ "vbat_pid_compensation", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.vbatPidCompensation, .config.lookup = { TABLE_OFF_ON } }, { "vbat_pid_compensation", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.vbatPidCompensation, .config.lookup = { TABLE_OFF_ON } },
{ "pid_at_min_throttle", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.pidAtMinThrottle, .config.lookup = { TABLE_OFF_ON } }, { "pid_at_min_throttle", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.pidAtMinThrottle, .config.lookup = { TABLE_OFF_ON } },
{ "iterm_throttle_gain", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.itermThrottleGain, .config.minmax = {0, 200 } }, { "anti_gravity_threshold", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.itermThrottleThreshold, .config.minmax = {20, 1000 } },
{ "setpoint_relax_ratio", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.setpointRelaxRatio, .config.minmax = {0, 100 } }, { "setpoint_relax_ratio", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.setpointRelaxRatio, .config.minmax = {0, 100 } },
{ "dterm_setpoint_weight", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.dtermSetpointWeight, .config.minmax = {0, 255 } }, { "dterm_setpoint_weight", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.dtermSetpointWeight, .config.minmax = {0, 255 } },
{ "yaw_rate_accel_limit", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yawRateAccelLimit, .config.minmax = {0, 1000 } }, { "yaw_accel_limit", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yawRateAccelLimit, .config.minmax = {0.1f, 50.0f } },
{ "rate_accel_limit", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.rateAccelLimit, .config.minmax = {0, 1000 } }, { "accel_limit", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.rateAccelLimit, .config.minmax = {0.1f, 50.0f } },
{ "accum_threshold", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.rollPitchItermIgnoreRate, .config.minmax = {15, 1000 } }, { "accum_threshold", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.rollPitchItermIgnoreRate, .config.minmax = {15, 1000 } },
{ "yaw_accum_threshold", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yawItermIgnoreRate, .config.minmax = {15, 1000 } }, { "yaw_accum_threshold", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yawItermIgnoreRate, .config.minmax = {15, 1000 } },

View File

@ -29,7 +29,7 @@
#include "drivers/rx_pwm.h" #include "drivers/rx_pwm.h"
#include "fc/config.h" #include "fc/config.h"
#include "fc/mw.h" #include "fc/fc_main.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "fc/runtime_config.h" #include "fc/runtime_config.h"