2 * This file is part of Cleanflight.
4 * Cleanflight 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 * Cleanflight 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 Cleanflight. If not, see <http://www.gnu.org/licenses/>.
28 #include "common/maths.h"
29 #include "common/axis.h"
31 #include "drivers/sensor.h"
32 #include "drivers/accgyro.h"
34 #include "sensors/sensors.h"
35 #include "sensors/acceleration.h"
36 #include "sensors/barometer.h"
37 #include "sensors/sonar.h"
41 #include "io/rc_controls.h"
42 #include "io/escservo.h"
44 #include "flight/mixer.h"
45 #include "flight/pid.h"
46 #include "flight/imu.h"
48 #include "config/runtime_config.h"
50 int32_t setVelocity
= 0;
51 uint8_t velocityControl
= 0;
52 int32_t errorVelocityI
= 0;
53 int32_t altHoldThrottleAdjustment
= 0;
55 int32_t vario
= 0; // variometer in cm/s
58 static barometerConfig_t
*barometerConfig
;
59 static pidProfile_t
*pidProfile
;
60 static rcControlsConfig_t
*rcControlsConfig
;
61 static escAndServoConfig_t
*escAndServoConfig
;
63 void configureAltitudeHold(
64 pidProfile_t
*initialPidProfile
,
65 barometerConfig_t
*intialBarometerConfig
,
66 rcControlsConfig_t
*initialRcControlsConfig
,
67 escAndServoConfig_t
*initialEscAndServoConfig
70 pidProfile
= initialPidProfile
;
71 barometerConfig
= intialBarometerConfig
;
72 rcControlsConfig
= initialRcControlsConfig
;
73 escAndServoConfig
= initialEscAndServoConfig
;
76 #if defined(BARO) || defined(SONAR)
78 static int16_t initialThrottleHold
;
79 static int32_t EstAlt
; // in cm
81 // 40hz update rate (20hz LPF on acc)
82 #define BARO_UPDATE_FREQUENCY_40HZ (1000 * 25)
84 #define DEGREES_80_IN_DECIDEGREES 800
86 static void applyMultirotorAltHold(void)
88 static uint8_t isAltHoldChanged
= 0;
89 // multirotor alt hold
90 if (rcControlsConfig
->alt_hold_fast_change
) {
92 if (ABS(rcData
[THROTTLE
] - initialThrottleHold
) > rcControlsConfig
->alt_hold_deadband
) {
95 rcCommand
[THROTTLE
] += (rcData
[THROTTLE
] > initialThrottleHold
) ? -rcControlsConfig
->alt_hold_deadband
: rcControlsConfig
->alt_hold_deadband
;
97 if (isAltHoldChanged
) {
101 rcCommand
[THROTTLE
] = constrain(initialThrottleHold
+ altHoldThrottleAdjustment
, escAndServoConfig
->minthrottle
, escAndServoConfig
->maxthrottle
);
104 // slow alt changes, mostly used for aerial photography
105 if (ABS(rcData
[THROTTLE
] - initialThrottleHold
) > rcControlsConfig
->alt_hold_deadband
) {
106 // set velocity proportional to stick movement +100 throttle gives ~ +50 cm/s
107 setVelocity
= (rcData
[THROTTLE
] - initialThrottleHold
) / 2;
109 isAltHoldChanged
= 1;
110 } else if (isAltHoldChanged
) {
113 isAltHoldChanged
= 0;
115 rcCommand
[THROTTLE
] = constrain(initialThrottleHold
+ altHoldThrottleAdjustment
, escAndServoConfig
->minthrottle
, escAndServoConfig
->maxthrottle
);
119 static void applyFixedWingAltHold(airplaneConfig_t
*airplaneConfig
)
121 // handle fixedwing-related althold. UNTESTED! and probably wrong
122 // most likely need to check changes on pitch channel and 'reset' althold similar to
123 // how throttle does it on multirotor
125 rcCommand
[PITCH
] += altHoldThrottleAdjustment
* airplaneConfig
->fixedwing_althold_dir
;
128 void applyAltHold(airplaneConfig_t
*airplaneConfig
)
130 if (STATE(FIXED_WING
)) {
131 applyFixedWingAltHold(airplaneConfig
);
133 applyMultirotorAltHold();
137 void updateAltHoldState(void)
139 // Baro alt hold activate
140 if (!IS_RC_MODE_ACTIVE(BOXBARO
)) {
141 DISABLE_FLIGHT_MODE(BARO_MODE
);
145 if (!FLIGHT_MODE(BARO_MODE
)) {
146 ENABLE_FLIGHT_MODE(BARO_MODE
);
148 initialThrottleHold
= rcData
[THROTTLE
];
150 altHoldThrottleAdjustment
= 0;
154 void updateSonarAltHoldState(void)
156 // Sonar alt hold activate
157 if (!IS_RC_MODE_ACTIVE(BOXSONAR
)) {
158 DISABLE_FLIGHT_MODE(SONAR_MODE
);
162 if (!FLIGHT_MODE(SONAR_MODE
)) {
163 ENABLE_FLIGHT_MODE(SONAR_MODE
);
165 initialThrottleHold
= rcData
[THROTTLE
];
167 altHoldThrottleAdjustment
= 0;
171 bool isThrustFacingDownwards(rollAndPitchInclination_t
*inclination
)
173 return ABS(inclination
->values
.rollDeciDegrees
) < DEGREES_80_IN_DECIDEGREES
&& ABS(inclination
->values
.pitchDeciDegrees
) < DEGREES_80_IN_DECIDEGREES
;
177 * This (poorly named) function merely returns whichever is higher, roll inclination or pitch inclination.
178 * //TODO: Fix this up. We could either actually return the angle between 'down' and the normal of the craft
179 * (my best interpretation of scalar 'tiltAngle') or rename the function.
181 int16_t calculateTiltAngle(rollAndPitchInclination_t
*inclination
)
183 return MAX(ABS(inclination
->values
.rollDeciDegrees
), ABS(inclination
->values
.pitchDeciDegrees
));
186 int32_t calculateAltHoldThrottleAdjustment(int32_t vel_tmp
, float accZ_tmp
, float accZ_old
)
192 if (!isThrustFacingDownwards(&inclination
)) {
196 // Altitude P-Controller
198 if (!velocityControl
) {
199 error
= constrain(AltHold
- EstAlt
, -500, 500);
200 error
= applyDeadband(error
, 10); // remove small P parameter to reduce noise near zero position
201 setVel
= constrain((pidProfile
->P8
[PIDALT
] * error
/ 128), -300, +300); // limit velocity to +/- 3 m/s
203 setVel
= setVelocity
;
205 // Velocity PID-Controller
208 error
= setVel
- vel_tmp
;
209 result
= constrain((pidProfile
->P8
[PIDVEL
] * error
/ 32), -300, +300);
212 errorVelocityI
+= (pidProfile
->I8
[PIDVEL
] * error
);
213 errorVelocityI
= constrain(errorVelocityI
, -(8192 * 200), (8192 * 200));
214 result
+= errorVelocityI
/ 8192; // I in range +/-200
217 result
-= constrain(pidProfile
->D8
[PIDVEL
] * (accZ_tmp
+ accZ_old
) / 512, -150, 150);
222 void calculateEstimatedAltitude(uint32_t currentTime
)
224 static uint32_t previousTime
;
231 int32_t sonarAlt
= -1;
232 static float accZ_old
= 0.0f
;
233 static float vel
= 0.0f
;
234 static float accAlt
= 0.0f
;
235 static int32_t lastBaroAlt
;
237 static int32_t baroAlt_offset
= 0;
238 float sonarTransition
;
244 dTime
= currentTime
- previousTime
;
245 if (dTime
< BARO_UPDATE_FREQUENCY_40HZ
)
248 previousTime
= currentTime
;
251 if (!isBaroCalibrationComplete()) {
252 performBaroCalibrationCycle();
257 BaroAlt
= baroCalculateAltitude();
263 tiltAngle
= calculateTiltAngle(&inclination
);
264 sonarAlt
= sonarRead();
265 sonarAlt
= sonarCalculateAltitude(sonarAlt
, tiltAngle
);
268 if (sonarAlt
> 0 && sonarAlt
< 200) {
269 baroAlt_offset
= BaroAlt
- sonarAlt
;
272 BaroAlt
-= baroAlt_offset
;
273 if (sonarAlt
> 0 && sonarAlt
<= 300) {
274 sonarTransition
= (300 - sonarAlt
) / 100.0f
;
275 BaroAlt
= sonarAlt
* sonarTransition
+ BaroAlt
* (1.0f
- sonarTransition
);
279 dt
= accTimeSum
* 1e-6f
; // delta acc reading time in seconds
281 // Integrator - velocity, cm/sec
283 accZ_tmp
= (float)accSum
[2] / (float)accSumCount
;
287 vel_acc
= accZ_tmp
* accVelScale
* (float)accTimeSum
;
289 // Integrator - Altitude in cm
290 accAlt
+= (vel_acc
* 0.5f
) * dt
+ vel
* dt
; // integrate velocity to get distance (x= a/2 * t^2)
291 accAlt
= accAlt
* barometerConfig
->baro_cf_alt
+ (float)BaroAlt
* (1.0f
- barometerConfig
->baro_cf_alt
); // complementary filter for altitude estimation (baro & acc)
294 #ifdef DEBUG_ALT_HOLD
295 debug
[1] = accSum
[2] / accSumCount
; // acceleration
296 debug
[2] = vel
; // velocity
297 debug
[3] = accAlt
; // height
300 imuResetAccelerationSum();
303 if (!isBaroCalibrationComplete()) {
308 if (sonarAlt
> 0 && sonarAlt
< 200) {
309 // the sonar has the best range
315 baroVel
= (BaroAlt
- lastBaroAlt
) * 1000000.0f
/ dTime
;
316 lastBaroAlt
= BaroAlt
;
318 baroVel
= constrain(baroVel
, -1500, 1500); // constrain baro velocity +/- 1500cm/s
319 baroVel
= applyDeadband(baroVel
, 10); // to reduce noise near zero
321 // apply Complimentary Filter to keep the calculated velocity based on baro velocity (i.e. near real velocity).
322 // By using CF it's possible to correct the drift of integrated accZ (velocity) without loosing the phase, i.e without delay
323 vel
= vel
* barometerConfig
->baro_cf_vel
+ baroVel
* (1.0f
- barometerConfig
->baro_cf_vel
);
324 vel_tmp
= lrintf(vel
);
327 vario
= applyDeadband(vel_tmp
, 5);
329 altHoldThrottleAdjustment
= calculateAltHoldThrottleAdjustment(vel_tmp
, accZ_tmp
, accZ_old
);
334 int32_t altitudeHoldGetEstimatedAltitude(void)