AT32F435 SD card support (#14018)
[betaflight.git] / src / main / flight / autopilot_multirotor.c
blobc70635599a976dde6430f3387ddec47292c3ec7d
1 /*
2 * This file is part of Betaflight.
4 * Betaflight is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
9 * Betaflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with Betaflight. If not, see <http://www.gnu.org/licenses/>.
18 #include <stdint.h>
19 #include <stdlib.h>
20 #include <stdbool.h>
21 #include <math.h>
23 #include "platform.h"
25 #ifndef USE_WING
27 #include "build/debug.h"
28 #include "common/axis.h"
29 #include "common/filter.h"
30 #include "common/maths.h"
31 #include "common/vector.h"
32 #include "fc/rc.h"
33 #include "fc/runtime_config.h"
35 #include "flight/imu.h"
36 #include "flight/position.h"
37 #include "rx/rx.h"
38 #include "sensors/gyro.h"
40 #include "pg/autopilot.h"
41 #include "autopilot.h"
43 #define ALTITUDE_P_SCALE 0.01f
44 #define ALTITUDE_I_SCALE 0.003f
45 #define ALTITUDE_D_SCALE 0.01f
46 #define ALTITUDE_F_SCALE 0.01f
47 #define POSITION_P_SCALE 0.0012f
48 #define POSITION_I_SCALE 0.0001f
49 #define POSITION_D_SCALE 0.0015f
50 #define POSITION_A_SCALE 0.0008f
51 #define UPSAMPLING_CUTOFF_HZ 5.0f
53 static pidCoefficient_t altitudePidCoeffs;
54 static pidCoefficient_t positionPidCoeffs;
56 static float altitudeI = 0.0f;
57 static float throttleOut = 0.0f;
59 typedef struct efPidAxis_s {
60 bool isStopping;
61 float previousDistance;
62 float previousVelocity;
63 float integral;
64 pt1Filter_t velocityLpf;
65 pt1Filter_t accelerationLpf;
66 } efPidAxis_t;
68 typedef enum {
69 // axes are for ENU system; it is different from current Betaflight code
70 LON = 0, // X, east
71 LAT // Y, north
72 } axisEF_e;
74 typedef struct autopilotState_s {
75 gpsLocation_t targetLocation; // active / current target
76 float sanityCheckDistance;
77 float upsampleLpfGain; // for the Body Frame upsample filter for pitch and roll
78 float vaLpfCutoff; // velocity + acceleration lowpass filter cutoff
79 bool sticksActive;
80 float maxAngle;
81 vector2_t pidSumBF; // pid output, updated on each GPS update, rotated to body frame
82 pt3Filter_t upsampleLpfBF[RP_AXIS_COUNT]; // upsampling filter
83 efPidAxis_t efAxis[EF_AXIS_COUNT];
84 } autopilotState_t;
86 static autopilotState_t ap = {
87 .sanityCheckDistance = 1000.0f,
88 .upsampleLpfGain = 1.0f,
89 .vaLpfCutoff = 1.0f,
90 .sticksActive = false,
93 float autopilotAngle[RP_AXIS_COUNT];
95 static void resetEFAxisFilters(efPidAxis_t* efAxis, const float vaGain)
97 pt1FilterInit(&efAxis->velocityLpf, vaGain);
98 pt1FilterInit(&efAxis->accelerationLpf, vaGain);
101 void resetEFAxisParams(efPidAxis_t *efAxis, const float vaGain)
103 // at start only
104 resetEFAxisFilters(efAxis, vaGain);
105 efAxis->isStopping = true; // Enter starting (deceleration) 'phase'
106 efAxis->integral = 0.0f;
109 static void resetUpsampleFilters(void)
111 for (unsigned i = 0; i < ARRAYLEN(ap.upsampleLpfBF); i++) {
112 pt3FilterInit(&ap.upsampleLpfBF[i], ap.upsampleLpfGain);
116 // get sanity distance based on speed
117 static inline float sanityCheckDistance(const float gpsGroundSpeedCmS)
119 return fmaxf(1000.0f, gpsGroundSpeedCmS * 2.0f);
120 // distance flown in 2s at current speed. with minimum of 10m
123 void resetPositionControl(const gpsLocation_t *initialTargetLocation, unsigned taskRateHz)
125 // from pos_hold.c (or other client) when initiating position hold at target location
126 ap.targetLocation = *initialTargetLocation;
127 ap.sticksActive = false;
128 // set sanity check distance according to groundspeed at start, minimum of 10m
129 ap.sanityCheckDistance = sanityCheckDistance(gpsSol.groundSpeed);
130 for (unsigned i = 0; i < ARRAYLEN(ap.efAxis); i++) {
131 // clear anything stored in the filter at first call
132 resetEFAxisParams(&ap.efAxis[i], 1.0f);
134 const float taskInterval = 1.0f / taskRateHz;
135 ap.upsampleLpfGain = pt3FilterGain(UPSAMPLING_CUTOFF_HZ, taskInterval); // 5Hz; normally at 100Hz task rate
136 resetUpsampleFilters(); // clear accumlator from previous iterations
139 void autopilotInit(void)
141 const apConfig_t *cfg = apConfig();
143 ap.sticksActive = false;
144 ap.maxAngle = cfg->max_angle;
145 altitudePidCoeffs.Kp = cfg->altitude_P * ALTITUDE_P_SCALE;
146 altitudePidCoeffs.Ki = cfg->altitude_I * ALTITUDE_I_SCALE;
147 altitudePidCoeffs.Kd = cfg->altitude_D * ALTITUDE_D_SCALE;
148 altitudePidCoeffs.Kf = cfg->altitude_F * ALTITUDE_F_SCALE;
149 positionPidCoeffs.Kp = cfg->position_P * POSITION_P_SCALE;
150 positionPidCoeffs.Ki = cfg->position_I * POSITION_I_SCALE;
151 positionPidCoeffs.Kd = cfg->position_D * POSITION_D_SCALE;
152 positionPidCoeffs.Kf = cfg->position_A * POSITION_A_SCALE; // Kf used for acceleration
153 // initialise filters with approximate filter gains; location isn't used at this point.
154 ap.upsampleLpfGain = pt3FilterGain(UPSAMPLING_CUTOFF_HZ, 0.01f); // 5Hz, assuming 100Hz task rate at init
155 resetUpsampleFilters();
156 // Initialise PT1 filters for velocity and acceleration in earth frame axes
157 ap.vaLpfCutoff = cfg->position_cutoff * 0.01f;
158 const float vaGain = pt1FilterGain(ap.vaLpfCutoff, 0.1f); // assume 10Hz GPS connection at start; value is overwritten before first filter use
159 for (unsigned i = 0; i < ARRAYLEN(ap.efAxis); i++) {
160 resetEFAxisFilters(&ap.efAxis[i], vaGain);
164 void resetAltitudeControl (void) {
165 altitudeI = 0.0f;
168 void altitudeControl(float targetAltitudeCm, float taskIntervalS, float targetAltitudeStep)
170 const float verticalVelocityCmS = getAltitudeDerivative();
171 const float altitudeErrorCm = targetAltitudeCm - getAltitudeCm();
172 const float altitudeP = altitudeErrorCm * altitudePidCoeffs.Kp;
174 // reduce the iTerm gain for errors greater than 200cm (2m), otherwise it winds up too much
175 const float itermRelax = (fabsf(altitudeErrorCm) < 200.0f) ? 1.0f : 0.1f;
176 altitudeI += altitudeErrorCm * altitudePidCoeffs.Ki * itermRelax * taskIntervalS;
177 // limit iTerm to not more than 200 throttle units
178 altitudeI = constrainf(altitudeI, -200.0f, 200.0f);
180 // increase D when velocity is high, typically when initiating hold at high vertical speeds
181 // 1.0 when less than 5 m/s, 2x at 10m/s, 2.5 at 20 m/s, 2.8 at 50 m/s, asymptotes towards max 3.0.
182 float dBoost = 1.0f;
184 const float startValue = 500.0f; // velocity at which D should start to increase
185 const float altDeriv = fabsf(verticalVelocityCmS);
186 if (altDeriv > startValue) {
187 const float ratio = altDeriv / startValue;
188 dBoost = (3.0f * ratio - 2.0f) / ratio;
192 const float altitudeD = verticalVelocityCmS * dBoost * altitudePidCoeffs.Kd;
194 const float altitudeF = targetAltitudeStep * altitudePidCoeffs.Kf;
196 const float hoverOffset = apConfig()->hover_throttle - PWM_RANGE_MIN;
197 float throttleOffset = altitudeP + altitudeI - altitudeD + altitudeF + hoverOffset;
199 const float tiltMultiplier = 1.0f / fmaxf(getCosTiltAngle(), 0.5f);
200 // 1 = flat, 1.3 at 40 degrees, 1.56 at 50 deg, max 2.0 at 60 degrees or higher
201 // note: the default limit of Angle Mode is 60 degrees
203 throttleOffset *= tiltMultiplier;
205 float newThrottle = PWM_RANGE_MIN + throttleOffset;
206 newThrottle = constrainf(newThrottle, apConfig()->throttle_min, apConfig()->throttle_max);
207 DEBUG_SET(DEBUG_AUTOPILOT_ALTITUDE, 0, lrintf(newThrottle)); // normal range 1000-2000 but is before constraint
209 newThrottle = scaleRangef(newThrottle, MAX(rxConfig()->mincheck, PWM_RANGE_MIN), PWM_RANGE_MAX, 0.0f, 1.0f);
211 throttleOut = constrainf(newThrottle, 0.0f, 1.0f);
213 DEBUG_SET(DEBUG_AUTOPILOT_ALTITUDE, 1, lrintf(tiltMultiplier * 100));
214 DEBUG_SET(DEBUG_AUTOPILOT_ALTITUDE, 3, lrintf(targetAltitudeCm));
215 DEBUG_SET(DEBUG_AUTOPILOT_ALTITUDE, 4, lrintf(altitudeP));
216 DEBUG_SET(DEBUG_AUTOPILOT_ALTITUDE, 5, lrintf(altitudeI));
217 DEBUG_SET(DEBUG_AUTOPILOT_ALTITUDE, 6, lrintf(-altitudeD));
218 DEBUG_SET(DEBUG_AUTOPILOT_ALTITUDE, 7, lrintf(altitudeF));
221 void setSticksActiveStatus(bool areSticksActive)
223 ap.sticksActive = areSticksActive;
226 void setTargetLocationByAxis(const gpsLocation_t* newTargetLocation, axisEF_e efAxisIdx)
227 // not used at present but needed by upcoming GPS code
229 if (efAxisIdx == LON) {
230 ap.targetLocation.lon = newTargetLocation->lon; // update East-West / / longitude position
231 } else {
232 ap.targetLocation.lat = newTargetLocation->lat; // update North-South / latitude position
236 bool positionControl(void)
238 unsigned debugAxis = gyroConfig()->gyro_filter_debug_axis;
239 static vector2_t debugGpsDistance = { 0 }; // keep last calculated distance for DEBUG
240 static vector2_t debugPidSumEF = { 0 }; // and last pidsum in EF
241 static uint16_t gpsStamp = 0;
242 if (gpsHasNewData(&gpsStamp)) {
243 const float gpsDataInterval = getGpsDataIntervalSeconds(); // interval for current GPS data value 0.05 - 2.5s
244 const float gpsDataFreq = getGpsDataFrequencyHz();
246 // get lat and long distances from current location (gpsSol.llh) to target location
247 vector2_t gpsDistance;
248 GPS_distance2d(&gpsSol.llh, &ap.targetLocation, &gpsDistance); // X is EW/lon, Y is NS/lat
249 debugGpsDistance = gpsDistance;
250 const float distanceNormCm = vector2Norm(&gpsDistance);
252 // ** Sanity check **
253 // primarily to detect flyaway from no Mag or badly oriented Mag
254 // must accept some overshoot at the start, especially if entering at high speed
255 if (distanceNormCm > ap.sanityCheckDistance) {
256 return false;
259 // update filters according to current GPS update rate
260 const float vaGain = pt1FilterGain(ap.vaLpfCutoff, gpsDataInterval);
261 const float iTermLeakGain = 1.0f - pt1FilterGainFromDelay(2.5f, gpsDataInterval); // 2.5s time constant
262 vector2_t pidSum = { 0 }; // P+I in loop, D+A added after the axis loop (after limiting it)
263 vector2_t pidDA; // D+A
265 for (axisEF_e efAxisIdx = LON; efAxisIdx <= LAT; efAxisIdx++) {
266 efPidAxis_t *efAxis = &ap.efAxis[efAxisIdx];
267 // separate PID controllers for longitude (EastWest or EW, X) and latitude (NorthSouth or NS, Y)
268 const float axisDistance = gpsDistance.v[efAxisIdx];
270 // ** P **
271 const float pidP = axisDistance * positionPidCoeffs.Kp;
272 pidSum.v[efAxisIdx] += pidP;
274 // ** I **
275 // only add to iTerm while in hold phase
276 efAxis->integral += efAxis->isStopping ? 0.0f : axisDistance * gpsDataInterval;
277 const float pidI = efAxis->integral * positionPidCoeffs.Ki;
278 pidSum.v[efAxisIdx] += pidI;
280 // ** D ** //
281 // Velocity derived from GPS position works better than module supplied GPS Speed and Heading information
283 const float velocity = (axisDistance - efAxis->previousDistance) * gpsDataFreq; // cm/s
284 efAxis->previousDistance = axisDistance;
285 pt1FilterUpdateCutoff(&efAxis->velocityLpf, vaGain);
286 const float velocityFiltered = pt1FilterApply(&efAxis->velocityLpf, velocity);
287 float pidD = velocityFiltered * positionPidCoeffs.Kd;
289 // differentiate velocity another time to get acceleration
290 float acceleration = (velocityFiltered - efAxis->previousVelocity) * gpsDataFreq;
291 efAxis->previousVelocity = velocityFiltered;
292 // apply second filter to acceleration (acc is filtered twice)
293 pt1FilterUpdateCutoff(&efAxis->accelerationLpf, vaGain);
294 const float accelerationFiltered = pt1FilterApply(&efAxis->accelerationLpf, acceleration);
295 const float pidA = accelerationFiltered * positionPidCoeffs.Kf;
297 if (ap.sticksActive) {
298 // sticks active 'phase', prepare to enter stopping
299 efAxis->isStopping = true;
300 // slowly leak iTerm away
301 efAxis->integral *= iTermLeakGain;
302 efAxis->previousDistance = 0.0f; // avoid D and A spikes
303 // rest is handled after axis loop
304 } else if (efAxis->isStopping) {
305 // 'phase' after sticks are centered, but before craft has stopped; in given Earth axis
306 pidD *= 1.6f; // aribitrary D boost to stop more quickly than usual
307 // detect when axis has nearly stopped by sign reversal of velocity (comparing sign of velocityFiltered, which is delayed, to velocity)
308 if (velocity * velocityFiltered < 0.0f) {
309 setTargetLocationByAxis(&gpsSol.llh, efAxisIdx); // reset target location for this axis, forcing P to zero
310 efAxis->previousDistance = 0.0f; // ensure minimal D jump from the updated location
311 efAxis->isStopping = false; // end the 'stopping' phase
312 if (ap.efAxis[LAT].isStopping == ap.efAxis[LON].isStopping) {
313 // when both axes have stopped moving, reset the sanity distance to 10m default
314 ap.sanityCheckDistance = sanityCheckDistance(1000);
318 pidDA.v[efAxisIdx] = pidD + pidA; // save DA here, processed after axis loop
319 if (debugAxis == efAxisIdx) {
320 DEBUG_SET(DEBUG_AUTOPILOT_POSITION, 0, lrintf(distanceNormCm)); // same for both axes
321 DEBUG_SET(DEBUG_AUTOPILOT_POSITION, 4, lrintf(pidP * 10));
322 DEBUG_SET(DEBUG_AUTOPILOT_POSITION, 5, lrintf(pidI * 10));
323 DEBUG_SET(DEBUG_AUTOPILOT_POSITION, 6, lrintf(pidD * 10));
324 DEBUG_SET(DEBUG_AUTOPILOT_POSITION, 7, lrintf(pidA * 10));
326 } // end for loop
329 // limit sum of D and A per axis based on total DA vector length, otherwise can be too aggressive when starting at speed
330 // limit is 35 degrees from D and A alone, arbitrary value. 20 is a bit too low, allows a lot of overshoot
331 // note: an angle of more than 35 degrees can still be achieved as P and I grow
332 const float maxDAAngle = 35.0f; // D+A limit in degrees; arbitrary angle
333 const float mag = vector2Norm(&pidDA);
334 if (mag > maxDAAngle) {
335 vector2Scale(&pidDA, &pidDA, maxDAAngle / mag);
339 // add constrained DA to sum
340 vector2Add(&pidSum, &pidSum, &pidDA);
341 debugPidSumEF = pidSum;
342 vector2_t anglesBF;
344 if (ap.sticksActive) {
345 // if a Position Hold deadband is set, and sticks are outside deadband, allow pilot control in angle mode
346 anglesBF = (vector2_t){{0, 0}}; // set output PIDS to 0; upsampling filter will smooth this
347 // reset target location each cycle (and set previousDistance to zero in for loop), to keep D current, and avoid a spike when stopping
348 ap.targetLocation = gpsSol.llh;
349 // keep updating sanity check distance while sticks are out because speed may get high
350 ap.sanityCheckDistance = sanityCheckDistance(gpsSol.groundSpeed);
351 } else {
352 // ** Rotate pid Sum to body frame, and convert it into pitch and roll **
353 // attitude.values.yaw increases clockwise from north
354 // PID is running in ENU, adapt angle (to 0deg = EAST);
355 // rotation is from EarthFrame to BodyFrame, no change of sign from heading
356 const float angle = DECIDEGREES_TO_RADIANS(attitude.values.yaw - 900);
357 vector2_t pidBodyFrame; // pid output in body frame; X is forward, Y is left
358 vector2Rotate(&pidBodyFrame, &pidSum, angle); // rotate by angle counterclockwise
359 anglesBF.v[AI_ROLL] = -pidBodyFrame.y; // negative roll to fly left
360 anglesBF.v[AI_PITCH] = pidBodyFrame.x; // positive pitch for forward
361 // limit angle vector to maxAngle
362 const float mag = vector2Norm(&anglesBF);
363 if (mag > ap.maxAngle && mag > 0.0f) {
364 vector2Scale(&anglesBF, &anglesBF, ap.maxAngle / mag);
367 ap.pidSumBF = anglesBF; // this value will be upsampled
370 // Final output to pid.c Angle Mode at 100Hz with PT3 upsampling
371 for (unsigned i = 0; i < RP_AXIS_COUNT; i++) {
372 // note: upsampling should really be done in earth frame, to avoid 10Hz wobbles if pilot yaws and the controller is applying significant pitch or roll
373 autopilotAngle[i] = pt3FilterApply(&ap.upsampleLpfBF[i], ap.pidSumBF.v[i]);
376 if (debugAxis < 2) {
377 // this is different from @ctzsnooze version
378 // debugAxis = 0: store longitude + roll
379 // debugAxis = 1: store latitude + pitch
380 DEBUG_SET(DEBUG_AUTOPILOT_POSITION, 1, lrintf(debugGpsDistance.v[debugAxis])); // cm
381 DEBUG_SET(DEBUG_AUTOPILOT_POSITION, 2, lrintf(debugPidSumEF.v[debugAxis] * 10)); // deg * 10
382 DEBUG_SET(DEBUG_AUTOPILOT_POSITION, 3, lrintf(autopilotAngle[debugAxis] * 10)); // deg * 10
384 return true;
387 bool isBelowLandingAltitude(void)
389 return getAltitudeCm() < 100.0f * apConfig()->landing_altitude_m;
392 float getAutopilotThrottle(void)
394 return throttleOut;
397 bool isAutopilotInControl(void)
399 return !ap.sticksActive;
402 #endif // !USE_WING