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/>.
27 #include "build/debug.h"
29 #include "common/axis.h"
30 #include "common/filter.h"
31 #include "common/maths.h"
32 #include "common/utils.h"
34 #include "config/config.h"
35 #include "drivers/time.h"
38 #include "fc/rc_controls.h"
39 #include "fc/rc_modes.h"
40 #include "fc/runtime_config.h"
42 #include "flight/autopilot.h"
43 #include "flight/failsafe.h"
44 #include "flight/imu.h"
45 #include "flight/pid.h"
46 #include "flight/position.h"
50 #include "pg/autopilot.h"
51 #include "sensors/acceleration.h"
53 #include "gps_rescue.h"
72 RESCUE_CRASHFLIP_DETECTED
,
76 } rescueFailureState_e
;
80 float returnAltitudeCm
;
81 float targetAltitudeCm
;
82 float targetAltitudeStepCm
;
83 float targetVelocityCmS
;
84 float pitchAngleLimitDeg
;
85 float rollAngleLimitDeg
;
86 float descentDistanceM
;
87 int8_t secondsFailing
;
89 float disarmThreshold
;
90 float velocityITermAccumulator
;
91 float velocityPidCutoff
;
92 float velocityPidCutoffModifier
;
93 float velocityItermAttenuator
;
94 float velocityItermRelax
;
98 float distanceToHomeCm
;
99 float distanceToHomeM
;
100 uint16_t groundSpeedCmS
;
101 int16_t directionToHome
;
104 float gpsDataIntervalSeconds
;
105 float velocityToHomeCmS
;
106 float alitutudeStepCm
;
110 } rescueSensorData_s
;
114 rescueFailureState_e failure
;
115 rescueSensorData_s sensor
;
116 rescueIntent_s intent
;
120 #define GPS_RESCUE_MAX_YAW_RATE 180 // deg/sec max yaw rate
121 #define GPS_RESCUE_MAX_THROTTLE_ITERM 200 // max iterm value for throttle in degrees * 100
122 #define GPS_RESCUE_ALLOWED_YAW_RANGE 30.0f // yaw error must be less than this to enter fly home phase, and to pitch during descend()
124 static const float taskIntervalSeconds
= HZ_TO_INTERVAL(TASK_GPS_RESCUE_RATE_HZ
); // i.e. 0.01 s
125 static float rescueYaw
;
126 float gpsRescueAngle
[RP_AXIS_COUNT
] = { 0, 0 };
127 bool magForceDisable
= false;
128 static pt1Filter_t velocityDLpf
;
129 static pt3Filter_t velocityUpsampleLpf
;
132 rescueState_s rescueState
;
134 void gpsRescueInit(void)
136 float cutoffHz
, gain
;
137 cutoffHz
= gpsRescueConfig()->pitchCutoffHz
/ 100.0f
;
138 rescueState
.intent
.velocityPidCutoff
= cutoffHz
;
139 rescueState
.intent
.velocityPidCutoffModifier
= 1.0f
;
140 gain
= pt1FilterGain(cutoffHz
, 1.0f
);
141 pt1FilterInit(&velocityDLpf
, gain
);
143 gain
= pt3FilterGain(cutoffHz
, taskIntervalSeconds
);
144 pt3FilterInit(&velocityUpsampleLpf
, gain
);
147 static void rescueStart(void)
149 rescueState
.phase
= RESCUE_INITIALIZE
;
152 static void rescueStop(void)
154 rescueState
.phase
= RESCUE_IDLE
;
157 // Things that need to run when GPS Rescue is enabled, and while armed, but while there is no Rescue in place
158 static void setReturnAltitude(bool newGpsData
)
160 // Hold maxAltitude at zero while disarmed, but if set_home_point_once is true, hold maxAlt until power cycled
161 if (!ARMING_FLAG(ARMED
) && !gpsConfig()->gps_set_home_point_once
) {
162 rescueState
.intent
.maxAltitudeCm
= 0.0f
;
166 // While armed, but not during the rescue, update the max altitude value
167 rescueState
.intent
.maxAltitudeCm
= fmaxf(getAltitudeCm(), rescueState
.intent
.maxAltitudeCm
);
170 // set the target altitude to the current altitude.
171 rescueState
.intent
.targetAltitudeCm
= getAltitudeCm();
173 // Intended descent distance for rescues that start outside the minStartDistM distance
174 // Set this to the user's intended descent distance, but not more than half the distance to home to ensure some fly home time
175 rescueState
.intent
.descentDistanceM
= fminf(0.5f
* rescueState
.sensor
.distanceToHomeM
, gpsRescueConfig()->descentDistanceM
);
177 const float initialClimbCm
= gpsRescueConfig()->initialClimbM
* 100.0f
;
178 switch (gpsRescueConfig()->altitudeMode
) {
179 case GPS_RESCUE_ALT_MODE_FIXED
:
180 rescueState
.intent
.returnAltitudeCm
= gpsRescueConfig()->returnAltitudeM
* 100.0f
;
182 case GPS_RESCUE_ALT_MODE_CURRENT
:
183 // climb above current altitude, but always return at least initial height above takeoff point, in case current altitude was negative
184 rescueState
.intent
.returnAltitudeCm
= fmaxf(initialClimbCm
, getAltitudeCm() + initialClimbCm
);
186 case GPS_RESCUE_ALT_MODE_MAX
:
188 rescueState
.intent
.returnAltitudeCm
= rescueState
.intent
.maxAltitudeCm
+ initialClimbCm
;
194 static void rescueAttainPosition(bool newGpsData
)
196 // runs at 100hz, but only updates RPYT settings when new GPS Data arrives and when not in idle phase.
197 static float previousVelocityError
= 0.0f
;
198 static float velocityI
= 0.0f
;
199 switch (rescueState
.phase
) {
201 // values to be returned when no rescue is active
202 gpsRescueAngle
[AI_PITCH
] = 0.0f
;
203 gpsRescueAngle
[AI_ROLL
] = 0.0f
;
205 case RESCUE_INITIALIZE
:
206 // Initialize internal variables each time GPS Rescue is started
207 previousVelocityError
= 0.0f
;
209 resetAltitudeControl();
210 rescueState
.intent
.disarmThreshold
= gpsRescueConfig()->disarmThreshold
* 0.1f
;
211 rescueState
.sensor
.imuYawCogGain
= 1.0f
;
213 case RESCUE_DO_NOTHING
:
214 // 20s of hover for switch induced sanity failures to allow time to recover
215 gpsRescueAngle
[AI_PITCH
] = 0.0f
;
216 gpsRescueAngle
[AI_ROLL
] = 0.0f
;
223 Altitude (throttle) controller
225 altitudeControl(rescueState
.intent
.targetAltitudeCm
, taskIntervalSeconds
, rescueState
.intent
.targetAltitudeStepCm
);
228 Heading / yaw controller
230 // simple yaw P controller with roll mixed in.
231 // attitude.values.yaw is set by imuCalculateEstimatedAttitude() and is updated from GPS while groundspeed exceeds 2 m/s
232 // below 2m/s groundspeed, the IMU uses gyro to estimate yaw attitude change from previous values
233 // above 2m/s, GPS course over ground us ysed to 'correct' the IMU heading
234 // if the course over ground, due to wind or pre-exiting movement, is different from the attitude of the quad, the GPS correction will be less accurate
235 // the craft should not return much less than 5m/s during the rescue or the GPS corrections may be inaccurate.
236 // the faster the return speed, the more accurate the IMU will be, but the consequences of IMU error at the start are greater
237 // A compass (magnetometer) is vital for accurate GPS rescue at slow speeds, but must be calibrated and validated
238 // WARNING: Some GPS units give false Home values! Always check the arrow points to home on leaving home.
239 rescueYaw
= rescueState
.sensor
.errorAngle
* gpsRescueConfig()->yawP
* rescueState
.intent
.yawAttenuator
/ 10.0f
;
240 rescueYaw
= constrainf(rescueYaw
, -GPS_RESCUE_MAX_YAW_RATE
, GPS_RESCUE_MAX_YAW_RATE
);
241 // rescueYaw is the yaw rate in deg/s to correct the heading error
243 // *** mix in some roll. very important for heading tracking, since a yaw rate means the quad has drifted sideways
244 const float rollMixAttenuator
= constrainf(1.0f
- fabsf(rescueYaw
) * 0.01f
, 0.0f
, 1.0f
);
245 // less roll at higher yaw rates, no roll at 100 deg/s of yaw
246 const float rollAdjustment
= -rescueYaw
* gpsRescueConfig()->rollMix
* rollMixAttenuator
;
247 // if rollMix = 100, the roll:yaw ratio is 1:1 at small angles, reducing linearly to zero when the yaw rate is 100 deg/s
248 // when gpsRescueConfig()->rollMix is zero, there is no roll adjustment
249 // rollAdjustment is degrees * 100
250 // note that the roll element has the opposite sign to the yaw element *before* GET_DIRECTION
251 const float rollLimit
= 100.0f
* rescueState
.intent
.rollAngleLimitDeg
;
252 gpsRescueAngle
[AI_ROLL
] = constrainf(rollAdjustment
, -rollLimit
, rollLimit
);
253 // gpsRescueAngle is added to the normal roll Angle Mode corrections in pid.c
255 rescueYaw
*= GET_DIRECTION(rcControlsConfig()->yaw_control_reversed
);
256 // rescueYaw is the yaw rate in deg/s to correct the heading error
258 DEBUG_SET(DEBUG_GPS_RESCUE_HEADING
, 5, rollMixAttenuator
); // 0-1 to suppress roll adjustments at higher yaw rates
259 DEBUG_SET(DEBUG_GPS_RESCUE_HEADING
, 6, gpsRescueAngle
[AI_ROLL
]); // roll added in degrees*100
260 DEBUG_SET(DEBUG_GPS_RESCUE_HEADING
, 7, rescueYaw
); // the yaw rate in deg/s to correct a yaw error
261 DEBUG_SET(DEBUG_GPS_RESCUE_TRACKING
, 7, gpsRescueAngle
[AI_ROLL
]); // roll added in degrees*100
264 Pitch / velocity controller
266 static float pitchAdjustment
= 0.0f
;
269 const float sampleIntervalNormaliseFactor
= rescueState
.sensor
.gpsDataIntervalSeconds
* 10.0f
;
271 const float velocityError
= rescueState
.intent
.targetVelocityCmS
- rescueState
.sensor
.velocityToHomeCmS
;
272 // velocityError is in cm per second, positive means too slow.
273 // NB positive pitch setpoint means nose down.
274 // target velocity can be very negative leading to large error before the start, with overshoot
277 const float velocityP
= velocityError
* gpsRescueConfig()->velP
;
280 velocityI
+= 0.01f
* gpsRescueConfig()->velI
* velocityError
* sampleIntervalNormaliseFactor
* rescueState
.intent
.velocityItermRelax
;
281 // velocityItermRelax is a time-based factor, 0->1 with time constant of 1s from when we start to fly home
282 // avoids excess iTerm accumulation during the initial acceleration phase and during descent.
284 velocityI
*= rescueState
.intent
.velocityItermAttenuator
;
285 // used to minimise iTerm windup during IMU error states and iTerm overshoot in the descent phase
286 // also, if we over-fly the home point, we need to re-accumulate iTerm from zero, not the previously accumulated value
288 const float pitchAngleLimit
= rescueState
.intent
.pitchAngleLimitDeg
* 100.0f
;
289 const float velocityILimit
= 0.5f
* pitchAngleLimit
;
290 // I component alone cannot exceed half the max pitch angle
291 velocityI
= constrainf(velocityI
, -velocityILimit
, velocityILimit
);
294 float velocityD
= ((velocityError
- previousVelocityError
) / sampleIntervalNormaliseFactor
);
295 previousVelocityError
= velocityError
;
296 velocityD
*= gpsRescueConfig()->velD
;
297 DEBUG_SET(DEBUG_GPS_RESCUE_VELOCITY
, 5, lrintf(velocityD
)); // velocity D before lowpass smoothing
298 // smooth the D steps
299 const float cutoffHz
= rescueState
.intent
.velocityPidCutoff
* rescueState
.intent
.velocityPidCutoffModifier
;
300 // note that this cutoff is increased up to 2x as we get closer to landing point in descend()
301 const float gain
= pt1FilterGain(cutoffHz
, rescueState
.sensor
.gpsDataIntervalSeconds
);
302 pt1FilterUpdateCutoff(&velocityDLpf
, gain
);
303 velocityD
= pt1FilterApply(&velocityDLpf
, velocityD
);
305 pitchAdjustment
= velocityP
+ velocityI
+ velocityD
;
306 // limit to maximum allowed angle
307 pitchAdjustment
= constrainf(pitchAdjustment
, -pitchAngleLimit
, pitchAngleLimit
);
309 // pitchAdjustment is the absolute Pitch angle adjustment value in degrees * 100
310 // it gets added to the normal level mode Pitch adjustments in pid.c
311 DEBUG_SET(DEBUG_GPS_RESCUE_VELOCITY
, 0, lrintf(velocityP
));
312 DEBUG_SET(DEBUG_GPS_RESCUE_VELOCITY
, 1, lrintf(velocityD
));
313 DEBUG_SET(DEBUG_GPS_RESCUE_VELOCITY
, 4, lrintf(velocityI
));
314 DEBUG_SET(DEBUG_GPS_RESCUE_VELOCITY
, 6, lrintf(rescueState
.intent
.velocityItermRelax
)); // factor attenuates velocity iTerm by multiplication
315 DEBUG_SET(DEBUG_GPS_RESCUE_VELOCITY
, 7, lrintf(pitchAdjustment
)); // rescue pitch angle in degrees * 100
318 // if initiated too close, and in the climb phase, pitch forward in whatever direction the nose is oriented until min distance away
319 // intent is to get far enough away that, with an IMU error, the quad will have enough distance to home to correct that error in the fly home phase
320 if (rescueState
.phase
== RESCUE_ATTAIN_ALT
&& rescueState
.sensor
.distanceToHomeM
< gpsRescueConfig()->minStartDistM
) {
321 pitchAdjustment
= 1500.0f
; // 15 degree pitch forward
324 // upsampling and smoothing of pitch angle steps
325 float pitchAdjustmentFiltered
= pt3FilterApply(&velocityUpsampleLpf
, pitchAdjustment
);
327 gpsRescueAngle
[AI_PITCH
] = pitchAdjustmentFiltered
;
328 // this angle gets added to the normal pitch Angle Mode control values in pid.c - will be seen in pitch setpoint
330 DEBUG_SET(DEBUG_GPS_RESCUE_VELOCITY
, 3, lrintf(rescueState
.intent
.targetVelocityCmS
)); // target velocity to home
331 DEBUG_SET(DEBUG_GPS_RESCUE_TRACKING
, 1, lrintf(rescueState
.intent
.targetVelocityCmS
)); // target velocity to home
334 static void performSanityChecks(void)
336 static timeUs_t previousTimeUs
= 0; // Last time Stalled/LowSat was checked
337 static float prevAltitudeCm
= 0.0f
; // to calculate ascent or descent change
338 static float prevTargetAltitudeCm
= 0.0f
; // to calculate ascent or descent target change
339 static float previousDistanceToHomeCm
= 0.0f
; // to check that we are returning
340 static int8_t secondsLowSats
= 0; // Minimum sat detection
341 static int8_t secondsDoingNothing
; // Limit on doing nothing
342 const timeUs_t currentTimeUs
= micros();
344 if (rescueState
.phase
== RESCUE_IDLE
) {
345 rescueState
.failure
= RESCUE_HEALTHY
;
347 } else if (rescueState
.phase
== RESCUE_INITIALIZE
) {
348 // Initialize these variables each time a GPS Rescue is started
349 previousTimeUs
= currentTimeUs
;
350 prevAltitudeCm
= getAltitudeCm();
351 prevTargetAltitudeCm
= rescueState
.intent
.targetAltitudeCm
;
352 previousDistanceToHomeCm
= rescueState
.sensor
.distanceToHomeCm
;
354 secondsDoingNothing
= 0;
357 // Handle events that set a failure mode to other than healthy.
358 // Disarm via Abort when sanity on, or for hard Rx loss in FS_ONLY mode
359 // Otherwise allow 20s of semi-controlled descent with impact disarm detection
360 const bool hardFailsafe
= !isRxReceivingSignal();
362 if (rescueState
.failure
!= RESCUE_HEALTHY
) {
363 // Default to 20s semi-controlled descent with impact detection, then abort
364 rescueState
.phase
= RESCUE_DO_NOTHING
;
366 switch(gpsRescueConfig()->sanityChecks
) {
367 case RESCUE_SANITY_ON
:
368 rescueState
.phase
= RESCUE_ABORT
;
370 case RESCUE_SANITY_FS_ONLY
:
372 rescueState
.phase
= RESCUE_ABORT
;
376 // even with sanity checks off,
377 // override when Allow Arming without Fix is enabled without GPS_FIX_HOME and no Control link available.
378 if (gpsRescueConfig()->allowArmingWithoutFix
&& !STATE(GPS_FIX_HOME
) && hardFailsafe
) {
379 rescueState
.phase
= RESCUE_ABORT
;
384 // Crash detection is enabled in all rescues. If triggered, immediately disarm.
385 if (crashRecoveryModeActive()) {
386 setArmingDisabled(ARMING_DISABLED_ARM_SWITCH
);
387 disarm(DISARM_REASON_CRASH_PROTECTION
);
391 // Check if GPS comms are healthy
392 // ToDo - check if we have an altitude reading; if we have Baro, we can use Landing mode for controlled descent without GPS
393 if (!rescueState
.sensor
.healthy
) {
394 rescueState
.failure
= RESCUE_GPSLOST
;
397 // Things that should run at a low refresh rate (such as flyaway detection, etc) will be checked at 1Hz
398 const timeDelta_t dTime
= cmpTimeUs(currentTimeUs
, previousTimeUs
);
399 if (dTime
< 1000000) { //1hz
402 previousTimeUs
= currentTimeUs
;
404 // checks that we are getting closer to home.
405 // if the quad is stuck, or if GPS data packets stop, there will be no change in distance to home
406 // we can't use rescueState.sensor.currentVelocity because it will be held at the last good value if GPS data updates stop
407 if (rescueState
.phase
== RESCUE_FLY_HOME
) {
408 const float velocityToHomeCmS
= previousDistanceToHomeCm
- rescueState
.sensor
.distanceToHomeCm
; // cm/s
409 previousDistanceToHomeCm
= rescueState
.sensor
.distanceToHomeCm
;
410 rescueState
.intent
.secondsFailing
+= (velocityToHomeCmS
< 0.1f
* rescueState
.intent
.targetVelocityCmS
) ? 1 : -1;
411 rescueState
.intent
.secondsFailing
= constrain(rescueState
.intent
.secondsFailing
, 0, 30);
412 if (rescueState
.intent
.secondsFailing
>= 30) {
414 //If there is a mag and has not been disabled, we have to assume is healthy and has been used in imu.c
415 if (sensors(SENSOR_MAG
) && gpsRescueConfig()->useMag
&& !magForceDisable
) {
416 //Try again with mag disabled
417 magForceDisable
= true;
418 rescueState
.intent
.secondsFailing
= 0;
422 rescueState
.failure
= RESCUE_FLYAWAY
;
427 secondsLowSats
+= (!STATE(GPS_FIX
) || (gpsSol
.numSat
< GPS_MIN_SAT_COUNT
)) ? 1 : -1;
428 secondsLowSats
= constrain(secondsLowSats
, 0, 10);
430 if (secondsLowSats
== 10) {
431 rescueState
.failure
= RESCUE_LOWSATS
;
434 // These conditions ignore sanity mode settings, and apply in all rescues, to handle getting stuck in a climb or descend
436 const float actualAltitudeChange
= getAltitudeCm() - prevAltitudeCm
;
437 // ** possibly could use getAltitudeDerivative() for for actual altitude change, though it is smoothed
438 const float targetAltitudeChange
= rescueState
.intent
.targetAltitudeCm
- prevTargetAltitudeCm
;
439 const float ratio
= actualAltitudeChange
/ targetAltitudeChange
;
440 prevAltitudeCm
= getAltitudeCm();
441 prevTargetAltitudeCm
= rescueState
.intent
.targetAltitudeCm
;
443 switch (rescueState
.phase
) {
445 rescueState
.intent
.secondsFailing
+= ratio
> 0.5f
? -1 : 1;
446 rescueState
.intent
.secondsFailing
= constrain(rescueState
.intent
.secondsFailing
, 0, 10);
447 if (rescueState
.intent
.secondsFailing
>= 10) {
448 rescueState
.phase
= RESCUE_ABORT
;
449 // Landing mode shouldn't take more than 10s
452 case RESCUE_ATTAIN_ALT
:
454 rescueState
.intent
.secondsFailing
+= ratio
> 0.5f
? -1 : 1;
455 rescueState
.intent
.secondsFailing
= constrain(rescueState
.intent
.secondsFailing
, 0, 10);
456 if (rescueState
.intent
.secondsFailing
>= 10) {
457 rescueState
.phase
= RESCUE_LANDING
;
458 rescueState
.intent
.secondsFailing
= 0;
459 // if can't climb, or slow descending, enable impact detection and time out in 10s
462 case RESCUE_DO_NOTHING
:
463 secondsDoingNothing
= MIN(secondsDoingNothing
+ 1, 20);
464 if (secondsDoingNothing
>= 20) {
465 rescueState
.phase
= RESCUE_ABORT
;
466 // time-limited semi-controlled fall with impact detection
474 DEBUG_SET(DEBUG_RTH
, 2, (rescueState
.failure
* 10 + rescueState
.phase
));
475 DEBUG_SET(DEBUG_RTH
, 3, (rescueState
.intent
.secondsFailing
* 100 + secondsLowSats
));
478 static void sensorUpdate(bool newGpsData
)
480 static float prevDistanceToHomeCm
= 0.0f
;
482 const float altitudeCurrentCm
= getAltitudeCm();
483 DEBUG_SET(DEBUG_GPS_RESCUE_TRACKING
, 2, lrintf(altitudeCurrentCm
));
484 DEBUG_SET(DEBUG_GPS_RESCUE_HEADING
, 0, rescueState
.sensor
.groundSpeedCmS
); // groundspeed cm/s
485 DEBUG_SET(DEBUG_GPS_RESCUE_HEADING
, 1, gpsSol
.groundCourse
); // degrees * 10
486 DEBUG_SET(DEBUG_GPS_RESCUE_HEADING
, 2, attitude
.values
.yaw
); // degrees * 10
487 DEBUG_SET(DEBUG_GPS_RESCUE_HEADING
, 3, rescueState
.sensor
.directionToHome
); // computed from current GPS position in relation to home
488 rescueState
.sensor
.healthy
= gpsIsHealthy();
490 rescueState
.sensor
.directionToHome
= GPS_directionToHome
; // extern value from gps.c using current position relative to home
491 rescueState
.sensor
.errorAngle
= (attitude
.values
.yaw
- rescueState
.sensor
.directionToHome
) / 10.0f
;
492 // both attitude and direction are in degrees * 10, errorAngle is degrees
493 if (rescueState
.sensor
.errorAngle
<= -180) {
494 rescueState
.sensor
.errorAngle
+= 360;
495 } else if (rescueState
.sensor
.errorAngle
> 180) {
496 rescueState
.sensor
.errorAngle
-= 360;
498 rescueState
.sensor
.absErrorAngle
= fabsf(rescueState
.sensor
.errorAngle
);
500 DEBUG_SET(DEBUG_GPS_RESCUE_TRACKING
, 4, lrintf(attitude
.values
.yaw
)); // estimated heading of the quad (direction nose is pointing in)
501 DEBUG_SET(DEBUG_GPS_RESCUE_TRACKING
, 5, lrintf(rescueState
.sensor
.directionToHome
)); // angle to home derived from GPS location and home position
505 // GPS ground speed, velocity and distance to home will be held at last good values if no new packets
508 rescueState
.sensor
.distanceToHomeCm
= GPS_distanceToHomeCm
;
509 rescueState
.sensor
.distanceToHomeM
= rescueState
.sensor
.distanceToHomeCm
/ 100.0f
;
510 rescueState
.sensor
.groundSpeedCmS
= gpsSol
.groundSpeed
; // cm/s
512 rescueState
.sensor
.gpsDataIntervalSeconds
= getGpsDataIntervalSeconds();
513 // Range from 50ms (20hz) to 2500ms (0.4Hz). Intended to cover common GPS data rates and exclude unusual values.
515 rescueState
.sensor
.velocityToHomeCmS
= ((prevDistanceToHomeCm
- rescueState
.sensor
.distanceToHomeCm
) * getGpsDataFrequencyHz());
516 // positive = towards home. First value is useless since prevDistanceToHomeCm was zero.
517 prevDistanceToHomeCm
= rescueState
.sensor
.distanceToHomeCm
;
519 DEBUG_SET(DEBUG_ATTITUDE
, 4, rescueState
.sensor
.velocityToHomeCmS
); // velocity to home
521 // when there is a flyaway due to IMU disorientation, increase IMU yaw CoG gain, and reduce max pitch angle
522 if (gpsRescueConfig()->groundSpeedCmS
) {
523 // calculate a factor that can reduce pitch angle when flying away
524 const float rescueGroundspeed
= gpsRescueConfig()->imuYawGain
* 100.0f
; // in cm/s, imuYawGain is m/s groundspeed
525 // rescueGroundspeed is effectively a normalising gain factor for the magnitude of the groundspeed error
526 // a higher value reduces groundspeedErrorRatio, making the radius wider and reducing the circling behaviour
528 const float groundspeedErrorRatio
= fabsf(rescueState
.sensor
.groundSpeedCmS
- rescueState
.sensor
.velocityToHomeCmS
) / rescueGroundspeed
;
529 // 0 if groundspeed = velocity to home, or both are zero
530 // 1 if forward velocity is zero but sideways speed is imuYawGain in m/s
531 // 2 if moving backwards at imuYawGain m/s, 4 if moving backwards at 2* imuYawGain m/s, etc
533 DEBUG_SET(DEBUG_ATTITUDE
, 5, groundspeedErrorRatio
* 100);
535 rescueState
.intent
.velocityItermAttenuator
= 4.0f
/ (groundspeedErrorRatio
+ 4.0f
);
536 // 1 if groundspeedErrorRatio = 0, falling to 2/3 if groundspeedErrorRatio = 2, 0.5 if groundspeedErrorRatio = 4, etc
537 // limit (essentially prevent) velocity iTerm accumulation whenever there is a meaningful groundspeed error
538 // this is a crude but simple way to prevent iTerm windup when recovering from an IMU error
539 // the magnitude of the effect will be less at low GPS data rates, since there will be fewer multiplications per second
540 // but for our purposes this should not matter much, our intent is to severely attenuate iTerm
541 // if, for example, we had a 90 degree attitude error, groundspeedErrorRatio = 1, invGroundspeedError = 0.8,
542 // after 10 iterations, iTerm is 0.1 of what it would have been
543 // also is useful in blocking iTerm accumulation if we overshoot the landing point
545 const float pitchForwardAngle
= (gpsRescueAngle
[AI_PITCH
] > 0.0f
) ? fminf(gpsRescueAngle
[AI_PITCH
] / 3000.0f
, 2.0f
) : 0.0f
;
546 // pitchForwardAngle is positive early in a rescue, and associates with a nose forward ground course
547 // note: gpsRescueAngle[AI_PITCH] is in degrees * 100, and is halved when the IMU is 180 wrong
548 // pitchForwardAngle is 0 when flat
549 // pitchForwardAngle is 0.5 if pitch angle is 15 degrees (ie with rescue angle of 30 and 180deg IMU error)
550 // pitchForwardAngle is 1.0 if pitch angle is 30 degrees (ie with rescue angle of 60 and 180deg IMU error)
551 // pitchForwardAngle is 2.0 if pitch angle is 60 degrees and flying towards home (unlikely to be sustained at that angle)
553 DEBUG_SET(DEBUG_ATTITUDE
, 6, pitchForwardAngle
* 100.0f
);
555 if (rescueState
.phase
!= RESCUE_FLY_HOME
) {
556 // prevent IMU disorientation arising from drift during climb, rotate or do nothing phases, which have zero pitch angle
557 // in descent, or too close, increase IMU yaw gain as pitch angle increases
558 rescueState
.sensor
.imuYawCogGain
= pitchForwardAngle
;
560 rescueState
.sensor
.imuYawCogGain
= pitchForwardAngle
+ fminf(groundspeedErrorRatio
, 3.5f
);
561 // imuYawCogGain will be more positive at higher pitch angles and higher groundspeed errors
562 // imuYawCogGain will be lowest (close to zero) at lower pitch angles and when flying straight towards home
566 DEBUG_SET(DEBUG_GPS_RESCUE_VELOCITY
, 2, lrintf(rescueState
.sensor
.velocityToHomeCmS
));
567 DEBUG_SET(DEBUG_GPS_RESCUE_TRACKING
, 0, lrintf(rescueState
.sensor
.velocityToHomeCmS
));
570 // This function flashes "RESCUE N/A" in the OSD if:
571 // 1. sensor healthy - GPS data is being received.
572 // 2. GPS has a 3D fix.
573 // 3. GPS number of satellites is greater than or equal to the minimum configured satellite count.
574 // Note 1: cannot arm without the required number of sats
575 // hence this flashing indicates that after having enough sats, we now have below the minimum and the rescue likely would fail
576 // Note 2: this function does not take into account the distance from home
577 // The sanity checks are independent, this just provides the OSD warning
578 static bool checkGPSRescueIsAvailable(void)
580 static timeUs_t previousTimeUs
= 0; // Last time LowSat was checked
581 const timeUs_t currentTimeUs
= micros();
582 static int8_t secondsLowSats
= 0; // Minimum sat detection
583 static bool lowsats
= false;
584 static bool noGPSfix
= false;
587 if (!gpsIsHealthy() || !STATE(GPS_FIX_HOME
)) {
591 // Things that should run at a low refresh rate >> ~1hz
592 const timeDelta_t dTime
= cmpTimeUs(currentTimeUs
, previousTimeUs
);
593 if (dTime
< 1000000) { //1hz
594 if (noGPSfix
|| lowsats
) {
600 previousTimeUs
= currentTimeUs
;
602 if (!STATE(GPS_FIX
)) {
609 secondsLowSats
= constrain(secondsLowSats
+ ((gpsSol
.numSat
< GPS_MIN_SAT_COUNT
) ? 1 : -1), 0, 2);
610 if (secondsLowSats
== 2) {
620 void disarmOnImpact(void)
622 if (acc
.accMagnitude
> rescueState
.intent
.disarmThreshold
) {
623 setArmingDisabled(ARMING_DISABLED_ARM_SWITCH
);
624 disarm(DISARM_REASON_GPS_RESCUE
);
629 void descend(bool newGpsData
)
632 // consider landing area to be a circle half landing height around home, to avoid overshooting home point
633 const float distanceToLandingAreaM
= rescueState
.sensor
.distanceToHomeM
- (0.5f
* apConfig()->landing_altitude_m
);
634 const float proximityToLandingArea
= constrainf(distanceToLandingAreaM
/ rescueState
.intent
.descentDistanceM
, 0.0f
, 1.0f
);
636 // increase the velocity lowpass filter cutoff for more aggressive responses when descending, especially close to home
637 // 1.5x when starting descent, 2.5x (smoother) when almost landed
638 rescueState
.intent
.velocityPidCutoffModifier
= 2.5f
- proximityToLandingArea
;
640 // reduce target velocity as we get closer to home. Zero within 2m of home, reducing risk of overshooting.
641 rescueState
.intent
.targetVelocityCmS
= gpsRescueConfig()->groundSpeedCmS
* proximityToLandingArea
;
643 // attenuate velocity target unless pointing towards home, to minimise circling behaviour during overshoots
644 if (rescueState
.sensor
.absErrorAngle
> GPS_RESCUE_ALLOWED_YAW_RANGE
) {
645 rescueState
.intent
.targetVelocityCmS
= 0;
647 rescueState
.intent
.targetVelocityCmS
*= (GPS_RESCUE_ALLOWED_YAW_RANGE
- rescueState
.sensor
.absErrorAngle
) / GPS_RESCUE_ALLOWED_YAW_RANGE
;
650 // attenuate velocity iterm towards zero as we get closer to the landing area
651 rescueState
.intent
.velocityItermAttenuator
= fminf(proximityToLandingArea
, rescueState
.intent
.velocityItermAttenuator
);
653 // full pitch angle available all the time
654 rescueState
.intent
.pitchAngleLimitDeg
= gpsRescueConfig()->maxRescueAngle
;
656 // limit roll angle to half the allowed pitch angle and attenuate when closer to home
657 // keep some roll when at the landing circle distance to avoid endless circling
658 const float proximityToHome
= constrainf(rescueState
.sensor
.distanceToHomeM
/ rescueState
.intent
.descentDistanceM
, 0.0f
, 1.0f
);
659 rescueState
.intent
.rollAngleLimitDeg
= 0.5f
* rescueState
.intent
.pitchAngleLimitDeg
* proximityToHome
;
662 // ensure we have full yaw authority in case we entered descent mode without enough time in fly home to acquire it gracefully
663 rescueState
.intent
.yawAttenuator
= 1.0f
;
665 // set the altitude step, considering the interval between altitude readings and the descent rate
666 float altitudeStepCm
= taskIntervalSeconds
* gpsRescueConfig()->descendRate
;
668 // at or below 10m: descend at 0.6x set value; above 10m, descend faster, to max 3.0x at 50m
669 altitudeStepCm
*= scaleRangef(constrainf(rescueState
.intent
.targetAltitudeCm
, 1000, 5000), 1000, 5000, 0.6f
, 3.0f
);
671 rescueState
.intent
.targetAltitudeStepCm
= -altitudeStepCm
;
672 rescueState
.intent
.targetAltitudeCm
-= altitudeStepCm
;
675 void initialiseRescueValues (void)
677 rescueState
.intent
.secondsFailing
= 0; // reset the sanity check timer
678 rescueState
.intent
.yawAttenuator
= 0.0f
; // no yaw in the climb
679 rescueState
.intent
.targetVelocityCmS
= rescueState
.sensor
.velocityToHomeCmS
; // avoid snap from D at the start
680 rescueState
.intent
.rollAngleLimitDeg
= 0.0f
; // no roll until flying home
681 rescueState
.intent
.velocityPidCutoffModifier
= 1.0f
; // normal velocity lowpass filter cutoff
682 rescueState
.intent
.pitchAngleLimitDeg
= 0.0f
; // force pitch adjustment to zero - level mode will level out
683 rescueState
.intent
.velocityItermAttenuator
= 1.0f
; // allow iTerm to accumulate normally unless constrained by IMU error or descent phase
684 rescueState
.intent
.velocityItermRelax
= 0.0f
; // but don't accumulate any at the start, not until fly home
685 rescueState
.intent
.targetAltitudeStepCm
= 0.0f
;
688 void gpsRescueUpdate(void)
689 // runs at gpsRescueTaskIntervalSeconds, and runs whether or not rescue is active
691 static uint16_t gpsStamp
= 0;
692 bool newGpsData
= gpsHasNewData(&gpsStamp
);
694 if (!FLIGHT_MODE(GPS_RESCUE_MODE
)) {
695 rescueStop(); // sets phase to RESCUE_IDLE; does nothing else. RESCUE_IDLE tasks still run.
696 } else if (FLIGHT_MODE(GPS_RESCUE_MODE
) && rescueState
.phase
== RESCUE_IDLE
) {
697 rescueStart(); // sets phase to rescue_initialise if we enter GPS Rescue mode while idle
698 rescueAttainPosition(false); // Initialise basic parameters when a Rescue starts (can't initialise sensor data reliably)
699 performSanityChecks(); // Initialises sanity check values when a Rescue starts
701 // Will now be in RESCUE_INITIALIZE mode, if just entered Rescue while IDLE, otherwise stays IDLE
703 sensorUpdate(newGpsData
); // always get latest GPS and Altitude data, update ascend and descend rates
705 static bool returnAltitudeLow
= true;
706 static bool initialVelocityLow
= true;
707 rescueState
.isAvailable
= checkGPSRescueIsAvailable();
709 switch (rescueState
.phase
) {
711 // in Idle phase = NOT in GPS Rescue
712 // update the return altitude and descent distance values, to have valid settings immediately they are needed
713 setReturnAltitude(newGpsData
);
715 // sanity checks are bypassed in IDLE mode; instead, failure state is always initialised to HEALTHY
716 // target altitude is always set to current altitude.
718 case RESCUE_INITIALIZE
:
719 // Things that should be done at the start of a Rescue
720 if (!STATE(GPS_FIX_HOME
)) {
721 // we didn't get a home point on arming
722 rescueState
.failure
= RESCUE_NO_HOME_POINT
;
723 // will result in a disarm via the sanity check system, or float around if switch induced
725 if (rescueState
.sensor
.distanceToHomeM
< 5.0f
&& isBelowLandingAltitude()) {
726 // attempted initiation within 5m of home, and 'on the ground' -> instant disarm, for safety reasons
727 rescueState
.phase
= RESCUE_ABORT
;
729 // attempted initiation within minimum rescue distance requires us to fly out to at least that distance
730 if (rescueState
.sensor
.distanceToHomeM
< gpsRescueConfig()->minStartDistM
) {
731 // climb above current height by buffer height, to at least 10m altitude
732 rescueState
.intent
.returnAltitudeCm
= fmaxf(1000.0f
, getAltitudeCm() + (gpsRescueConfig()->initialClimbM
* 100.0f
));
733 // note that the pitch controller will pitch forward to fly out to minStartDistM
734 // set the descent distance to half the minimum rescue distance. which we should have moved out to in the climb phase
735 rescueState
.intent
.descentDistanceM
= 0.5f
* gpsRescueConfig()->minStartDistM
;
737 // otherwise behave as for a normal rescue
738 initialiseRescueValues ();
739 returnAltitudeLow
= getAltitudeCm() < rescueState
.intent
.returnAltitudeCm
;
740 rescueState
.phase
= RESCUE_ATTAIN_ALT
;
745 case RESCUE_ATTAIN_ALT
:
746 // gradually increment the target altitude until the craft reaches target altitude
747 // note that this can mean the target altitude may increase above returnAltitude if the craft lags target
748 // sanity check will abort if altitude gain is blocked for a cumulative period
749 if (returnAltitudeLow
== (getAltitudeCm() < rescueState
.intent
.returnAltitudeCm
)) {
750 // we started low, and still are low; also true if we started high, and still are too high
751 rescueState
.intent
.targetAltitudeStepCm
= (returnAltitudeLow
? gpsRescueConfig()->ascendRate
: -1.0f
* gpsRescueConfig()->descendRate
) * taskIntervalSeconds
;
752 rescueState
.intent
.targetAltitudeCm
+= rescueState
.intent
.targetAltitudeStepCm
;
755 // target altitude achieved - move on to ROTATE phase, returning at target altitude
756 rescueState
.intent
.targetAltitudeCm
= rescueState
.intent
.returnAltitudeCm
;
757 rescueState
.intent
.targetAltitudeStepCm
= 0.0f
;
758 // if initiated too close, do not rotate or do anything else until sufficiently far away that a 'normal' rescue can happen
759 if (rescueState
.sensor
.distanceToHomeM
> gpsRescueConfig()->minStartDistM
) {
760 rescueState
.phase
= RESCUE_ROTATE
;
764 // give velocity P and I no error that otherwise could be present due to velocity drift at the start of the rescue
765 rescueState
.intent
.targetVelocityCmS
= rescueState
.sensor
.velocityToHomeCmS
;
769 if (rescueState
.intent
.yawAttenuator
< 1.0f
) { // acquire yaw authority over one second
770 rescueState
.intent
.yawAttenuator
+= taskIntervalSeconds
;
772 if (rescueState
.sensor
.absErrorAngle
< GPS_RESCUE_ALLOWED_YAW_RANGE
) {
773 // enter fly home phase, and enable pitch, when the yaw angle error is small enough
774 rescueState
.intent
.pitchAngleLimitDeg
= gpsRescueConfig()->maxRescueAngle
;
775 rescueState
.phase
= RESCUE_FLY_HOME
; // enter fly home phase
776 rescueState
.intent
.secondsFailing
= 0; // reset sanity timer for flight home
778 initialVelocityLow
= rescueState
.sensor
.velocityToHomeCmS
< gpsRescueConfig()->groundSpeedCmS
; // used to set direction of velocity target change
779 rescueState
.intent
.targetVelocityCmS
= rescueState
.sensor
.velocityToHomeCmS
;
782 case RESCUE_FLY_HOME
:
783 if (rescueState
.intent
.yawAttenuator
< 1.0f
) { // be sure to accumulate full yaw authority
784 rescueState
.intent
.yawAttenuator
+= taskIntervalSeconds
;
786 // velocity PIDs are now active
787 // update target velocity gradually, aiming for rescueGroundspeed with a time constant of 1.0s
788 const float targetVelocityError
= gpsRescueConfig()->groundSpeedCmS
- rescueState
.intent
.targetVelocityCmS
;
789 const float velocityTargetStep
= taskIntervalSeconds
* targetVelocityError
;
790 // velocityTargetStep is positive when starting low, negative when starting high
791 const bool targetVelocityIsLow
= rescueState
.intent
.targetVelocityCmS
< gpsRescueConfig()->groundSpeedCmS
;
792 if (initialVelocityLow
== targetVelocityIsLow
) {
793 // also true if started faster than target velocity and target is still high
794 rescueState
.intent
.targetVelocityCmS
+= velocityTargetStep
;
797 // slowly introduce velocity iTerm accumulation at start, goes 0 ->1 with time constant 2.0s
798 rescueState
.intent
.velocityItermRelax
+= 0.5f
* taskIntervalSeconds
* (1.0f
- rescueState
.intent
.velocityItermRelax
);
799 // there is always a lot of lag at the start, this gradual start avoids excess iTerm accumulation
801 rescueState
.intent
.velocityPidCutoffModifier
= 2.0f
- rescueState
.intent
.velocityItermRelax
;
802 // higher velocity filter cutoff for initial few seconds to improve accuracy; can be smoother later
805 // cut back on allowed angle if there is a high groundspeed error
806 rescueState
.intent
.pitchAngleLimitDeg
= gpsRescueConfig()->maxRescueAngle
;
807 // introduce roll slowly and limit to half the max pitch angle; earth referenced yaw may add more roll via angle code
808 rescueState
.intent
.rollAngleLimitDeg
= 0.5f
* rescueState
.intent
.pitchAngleLimitDeg
* rescueState
.intent
.velocityItermRelax
;
809 if (rescueState
.sensor
.distanceToHomeM
<= rescueState
.intent
.descentDistanceM
) {
810 rescueState
.phase
= RESCUE_DESCENT
;
811 rescueState
.intent
.secondsFailing
= 0; // reset sanity timer for descent
817 // attenuate velocity and altitude targets while updating the heading to home
818 if (isBelowLandingAltitude()) {
819 // enter landing mode once below landing altitude
820 rescueState
.phase
= RESCUE_LANDING
;
821 rescueState
.intent
.secondsFailing
= 0; // reset sanity timer for landing
827 // Reduce altitude target steadily until impact, then disarm.
828 // control yaw angle and throttle and pitch, attenuate velocity, roll and pitch iTerm
829 // increase velocity smoothing cutoff as we get closer to ground
835 setArmingDisabled(ARMING_DISABLED_ARM_SWITCH
);
836 disarm(DISARM_REASON_FAILSAFE
);
837 rescueState
.intent
.secondsFailing
= 0; // reset sanity timers so we can re-arm
841 case RESCUE_DO_NOTHING
:
849 DEBUG_SET(DEBUG_GPS_RESCUE_TRACKING
, 3, lrintf(rescueState
.intent
.targetAltitudeCm
));
850 DEBUG_SET(DEBUG_RTH
, 0, lrintf(rescueState
.intent
.maxAltitudeCm
/ 10.0f
));
852 performSanityChecks();
853 rescueAttainPosition(newGpsData
);
856 float gpsRescueGetYawRate(void)
858 return rescueYaw
; // the control yaw value for rc.c to be used while flightMode gps_rescue is active.
861 float gpsRescueGetImuYawCogGain(void)
863 return rescueState
.sensor
.imuYawCogGain
; // to speed up the IMU orientation to COG when needed
866 bool gpsRescueIsConfigured(void)
868 return failsafeConfig()->failsafe_procedure
== FAILSAFE_PROCEDURE_GPS_RESCUE
|| isModeActivationConditionPresent(BOXGPSRESCUE
);
871 bool gpsRescueIsAvailable(void)
873 return rescueState
.isAvailable
; // flashes the warning when not available (low sats, etc)
876 bool gpsRescueIsDisabled(void)
877 // used for OSD warning, needs review
879 return (!STATE(GPS_FIX_HOME
));
883 bool gpsRescueDisableMag(void)
885 // Enable mag on user request, but don't use it during fly home or if force disabled
886 // Note that while flying home the course over ground from GPS provides a heading that is less affected by wind
887 return !(gpsRescueConfig()->useMag
&& rescueState
.phase
!= RESCUE_FLY_HOME
&& !magForceDisable
);