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/>.
26 #include "build/debug.h"
28 #include "common/axis.h"
29 #include "common/filter.h"
30 #include "common/maths.h"
31 #include "common/utils.h"
33 #include "config/config.h"
34 #include "drivers/time.h"
37 #include "fc/rc_controls.h"
38 #include "fc/rc_modes.h"
39 #include "fc/runtime_config.h"
41 #include "flight/autopilot.h"
42 #include "flight/failsafe.h"
43 #include "flight/imu.h"
44 #include "flight/pid.h"
45 #include "flight/position.h"
49 #include "pg/autopilot.h"
50 #include "sensors/acceleration.h"
52 #include "gps_rescue.h"
71 RESCUE_CRASHFLIP_DETECTED
,
75 } rescueFailureState_e
;
79 float returnAltitudeCm
;
80 float targetAltitudeCm
;
81 float targetAltitudeStepCm
;
82 float targetVelocityCmS
;
83 float pitchAngleLimitDeg
;
84 float rollAngleLimitDeg
;
85 float descentDistanceM
;
86 int8_t secondsFailing
;
88 float disarmThreshold
;
89 float velocityITermAccumulator
;
90 float velocityPidCutoff
;
91 float velocityPidCutoffModifier
;
92 float velocityItermAttenuator
;
93 float velocityItermRelax
;
97 float distanceToHomeCm
;
98 float distanceToHomeM
;
99 uint16_t groundSpeedCmS
;
100 int16_t directionToHome
;
103 float gpsDataIntervalSeconds
;
104 float velocityToHomeCmS
;
105 float alitutudeStepCm
;
109 } rescueSensorData_s
;
113 rescueFailureState_e failure
;
114 rescueSensorData_s sensor
;
115 rescueIntent_s intent
;
119 #define GPS_RESCUE_MAX_YAW_RATE 180 // deg/sec max yaw rate
120 #define GPS_RESCUE_MAX_THROTTLE_ITERM 200 // max iterm value for throttle in degrees * 100
121 #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()
123 static const float taskIntervalSeconds
= HZ_TO_INTERVAL(TASK_GPS_RESCUE_RATE_HZ
); // i.e. 0.01 s
124 static float rescueYaw
;
125 float gpsRescueAngle
[RP_AXIS_COUNT
] = { 0, 0 };
126 bool magForceDisable
= false;
127 static pt1Filter_t velocityDLpf
;
128 static pt3Filter_t velocityUpsampleLpf
;
131 rescueState_s rescueState
;
133 void gpsRescueInit(void)
135 float cutoffHz
, gain
;
136 cutoffHz
= gpsRescueConfig()->pitchCutoffHz
/ 100.0f
;
137 rescueState
.intent
.velocityPidCutoff
= cutoffHz
;
138 rescueState
.intent
.velocityPidCutoffModifier
= 1.0f
;
139 gain
= pt1FilterGain(cutoffHz
, 1.0f
);
140 pt1FilterInit(&velocityDLpf
, gain
);
142 gain
= pt3FilterGain(cutoffHz
, taskIntervalSeconds
);
143 pt3FilterInit(&velocityUpsampleLpf
, gain
);
146 static void rescueStart(void)
148 rescueState
.phase
= RESCUE_INITIALIZE
;
151 static void rescueStop(void)
153 rescueState
.phase
= RESCUE_IDLE
;
156 // Things that need to run when GPS Rescue is enabled, and while armed, but while there is no Rescue in place
157 static void setReturnAltitude(bool newGpsData
)
159 // Hold maxAltitude at zero while disarmed, but if set_home_point_once is true, hold maxAlt until power cycled
160 if (!ARMING_FLAG(ARMED
) && !gpsConfig()->gps_set_home_point_once
) {
161 rescueState
.intent
.maxAltitudeCm
= 0.0f
;
165 // While armed, but not during the rescue, update the max altitude value
166 rescueState
.intent
.maxAltitudeCm
= fmaxf(getAltitudeCm(), rescueState
.intent
.maxAltitudeCm
);
169 // set the target altitude to the current altitude.
170 rescueState
.intent
.targetAltitudeCm
= getAltitudeCm();
172 // Intended descent distance for rescues that start outside the minStartDistM distance
173 // Set this to the user's intended descent distance, but not more than half the distance to home to ensure some fly home time
174 rescueState
.intent
.descentDistanceM
= fminf(0.5f
* rescueState
.sensor
.distanceToHomeM
, gpsRescueConfig()->descentDistanceM
);
176 const float initialClimbCm
= gpsRescueConfig()->initialClimbM
* 100.0f
;
177 switch (gpsRescueConfig()->altitudeMode
) {
178 case GPS_RESCUE_ALT_MODE_FIXED
:
179 rescueState
.intent
.returnAltitudeCm
= gpsRescueConfig()->returnAltitudeM
* 100.0f
;
181 case GPS_RESCUE_ALT_MODE_CURRENT
:
182 // climb above current altitude, but always return at least initial height above takeoff point, in case current altitude was negative
183 rescueState
.intent
.returnAltitudeCm
= fmaxf(initialClimbCm
, getAltitudeCm() + initialClimbCm
);
185 case GPS_RESCUE_ALT_MODE_MAX
:
187 rescueState
.intent
.returnAltitudeCm
= rescueState
.intent
.maxAltitudeCm
+ initialClimbCm
;
193 static void rescueAttainPosition(bool newGpsData
)
195 // runs at 100hz, but only updates RPYT settings when new GPS Data arrives and when not in idle phase.
196 static float previousVelocityError
= 0.0f
;
197 static float velocityI
= 0.0f
;
198 switch (rescueState
.phase
) {
200 // values to be returned when no rescue is active
201 gpsRescueAngle
[AI_PITCH
] = 0.0f
;
202 gpsRescueAngle
[AI_ROLL
] = 0.0f
;
204 case RESCUE_INITIALIZE
:
205 // Initialize internal variables each time GPS Rescue is started
206 previousVelocityError
= 0.0f
;
208 resetAltitudeControl();
209 rescueState
.intent
.disarmThreshold
= gpsRescueConfig()->disarmThreshold
* 0.1f
;
210 rescueState
.sensor
.imuYawCogGain
= 1.0f
;
212 case RESCUE_DO_NOTHING
:
213 // 20s of hover for switch induced sanity failures to allow time to recover
214 gpsRescueAngle
[AI_PITCH
] = 0.0f
;
215 gpsRescueAngle
[AI_ROLL
] = 0.0f
;
222 Altitude (throttle) controller
224 altitudeControl(rescueState
.intent
.targetAltitudeCm
, taskIntervalSeconds
, rescueState
.intent
.targetAltitudeStepCm
);
227 Heading / yaw controller
229 // simple yaw P controller with roll mixed in.
230 // attitude.values.yaw is set by imuCalculateEstimatedAttitude() and is updated from GPS while groundspeed exceeds 2 m/s
231 // below 2m/s groundspeed, the IMU uses gyro to estimate yaw attitude change from previous values
232 // above 2m/s, GPS course over ground us ysed to 'correct' the IMU heading
233 // 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
234 // the craft should not return much less than 5m/s during the rescue or the GPS corrections may be inaccurate.
235 // the faster the return speed, the more accurate the IMU will be, but the consequences of IMU error at the start are greater
236 // A compass (magnetometer) is vital for accurate GPS rescue at slow speeds, but must be calibrated and validated
237 // WARNING: Some GPS units give false Home values! Always check the arrow points to home on leaving home.
238 rescueYaw
= rescueState
.sensor
.errorAngle
* gpsRescueConfig()->yawP
* rescueState
.intent
.yawAttenuator
/ 10.0f
;
239 rescueYaw
= constrainf(rescueYaw
, -GPS_RESCUE_MAX_YAW_RATE
, GPS_RESCUE_MAX_YAW_RATE
);
240 // rescueYaw is the yaw rate in deg/s to correct the heading error
242 // *** mix in some roll. very important for heading tracking, since a yaw rate means the quad has drifted sideways
243 const float rollMixAttenuator
= constrainf(1.0f
- fabsf(rescueYaw
) * 0.01f
, 0.0f
, 1.0f
);
244 // less roll at higher yaw rates, no roll at 100 deg/s of yaw
245 const float rollAdjustment
= -rescueYaw
* gpsRescueConfig()->rollMix
* rollMixAttenuator
;
246 // 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
247 // when gpsRescueConfig()->rollMix is zero, there is no roll adjustment
248 // rollAdjustment is degrees * 100
249 // note that the roll element has the opposite sign to the yaw element *before* GET_DIRECTION
250 const float rollLimit
= 100.0f
* rescueState
.intent
.rollAngleLimitDeg
;
251 gpsRescueAngle
[AI_ROLL
] = constrainf(rollAdjustment
, -rollLimit
, rollLimit
);
252 // gpsRescueAngle is added to the normal roll Angle Mode corrections in pid.c
254 rescueYaw
*= GET_DIRECTION(rcControlsConfig()->yaw_control_reversed
);
255 // rescueYaw is the yaw rate in deg/s to correct the heading error
257 DEBUG_SET(DEBUG_GPS_RESCUE_HEADING
, 5, rollMixAttenuator
); // 0-1 to suppress roll adjustments at higher yaw rates
258 DEBUG_SET(DEBUG_GPS_RESCUE_HEADING
, 6, gpsRescueAngle
[AI_ROLL
]); // roll added in degrees*100
259 DEBUG_SET(DEBUG_GPS_RESCUE_HEADING
, 7, rescueYaw
); // the yaw rate in deg/s to correct a yaw error
260 DEBUG_SET(DEBUG_GPS_RESCUE_TRACKING
, 7, gpsRescueAngle
[AI_ROLL
]); // roll added in degrees*100
263 Pitch / velocity controller
265 static float pitchAdjustment
= 0.0f
;
268 const float sampleIntervalNormaliseFactor
= rescueState
.sensor
.gpsDataIntervalSeconds
* 10.0f
;
270 const float velocityError
= rescueState
.intent
.targetVelocityCmS
- rescueState
.sensor
.velocityToHomeCmS
;
271 // velocityError is in cm per second, positive means too slow.
272 // NB positive pitch setpoint means nose down.
273 // target velocity can be very negative leading to large error before the start, with overshoot
276 const float velocityP
= velocityError
* gpsRescueConfig()->velP
;
279 velocityI
+= 0.01f
* gpsRescueConfig()->velI
* velocityError
* sampleIntervalNormaliseFactor
* rescueState
.intent
.velocityItermRelax
;
280 // velocityItermRelax is a time-based factor, 0->1 with time constant of 1s from when we start to fly home
281 // avoids excess iTerm accumulation during the initial acceleration phase and during descent.
283 velocityI
*= rescueState
.intent
.velocityItermAttenuator
;
284 // used to minimise iTerm windup during IMU error states and iTerm overshoot in the descent phase
285 // also, if we over-fly the home point, we need to re-accumulate iTerm from zero, not the previously accumulated value
287 const float pitchAngleLimit
= rescueState
.intent
.pitchAngleLimitDeg
* 100.0f
;
288 const float velocityILimit
= 0.5f
* pitchAngleLimit
;
289 // I component alone cannot exceed half the max pitch angle
290 velocityI
= constrainf(velocityI
, -velocityILimit
, velocityILimit
);
293 float velocityD
= ((velocityError
- previousVelocityError
) / sampleIntervalNormaliseFactor
);
294 previousVelocityError
= velocityError
;
295 velocityD
*= gpsRescueConfig()->velD
;
296 DEBUG_SET(DEBUG_GPS_RESCUE_VELOCITY
, 5, lrintf(velocityD
)); // velocity D before lowpass smoothing
297 // smooth the D steps
298 const float cutoffHz
= rescueState
.intent
.velocityPidCutoff
* rescueState
.intent
.velocityPidCutoffModifier
;
299 // note that this cutoff is increased up to 2x as we get closer to landing point in descend()
300 const float gain
= pt1FilterGain(cutoffHz
, rescueState
.sensor
.gpsDataIntervalSeconds
);
301 pt1FilterUpdateCutoff(&velocityDLpf
, gain
);
302 velocityD
= pt1FilterApply(&velocityDLpf
, velocityD
);
304 pitchAdjustment
= velocityP
+ velocityI
+ velocityD
;
305 // limit to maximum allowed angle
306 pitchAdjustment
= constrainf(pitchAdjustment
, -pitchAngleLimit
, pitchAngleLimit
);
308 // pitchAdjustment is the absolute Pitch angle adjustment value in degrees * 100
309 // it gets added to the normal level mode Pitch adjustments in pid.c
310 DEBUG_SET(DEBUG_GPS_RESCUE_VELOCITY
, 0, lrintf(velocityP
));
311 DEBUG_SET(DEBUG_GPS_RESCUE_VELOCITY
, 1, lrintf(velocityD
));
312 DEBUG_SET(DEBUG_GPS_RESCUE_VELOCITY
, 4, lrintf(velocityI
));
313 DEBUG_SET(DEBUG_GPS_RESCUE_VELOCITY
, 6, lrintf(rescueState
.intent
.velocityItermRelax
)); // factor attenuates velocity iTerm by multiplication
314 DEBUG_SET(DEBUG_GPS_RESCUE_VELOCITY
, 7, lrintf(pitchAdjustment
)); // rescue pitch angle in degrees * 100
317 // if initiated too close, and in the climb phase, pitch forward in whatever direction the nose is oriented until min distance away
318 // 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
319 if (rescueState
.phase
== RESCUE_ATTAIN_ALT
&& rescueState
.sensor
.distanceToHomeM
< gpsRescueConfig()->minStartDistM
) {
320 pitchAdjustment
= 1500.0f
; // 15 degree pitch forward
323 // upsampling and smoothing of pitch angle steps
324 float pitchAdjustmentFiltered
= pt3FilterApply(&velocityUpsampleLpf
, pitchAdjustment
);
326 gpsRescueAngle
[AI_PITCH
] = pitchAdjustmentFiltered
;
327 // this angle gets added to the normal pitch Angle Mode control values in pid.c - will be seen in pitch setpoint
329 DEBUG_SET(DEBUG_GPS_RESCUE_VELOCITY
, 3, lrintf(rescueState
.intent
.targetVelocityCmS
)); // target velocity to home
330 DEBUG_SET(DEBUG_GPS_RESCUE_TRACKING
, 1, lrintf(rescueState
.intent
.targetVelocityCmS
)); // target velocity to home
333 static void performSanityChecks(void)
335 static timeUs_t previousTimeUs
= 0; // Last time Stalled/LowSat was checked
336 static float prevAltitudeCm
= 0.0f
; // to calculate ascent or descent change
337 static float prevTargetAltitudeCm
= 0.0f
; // to calculate ascent or descent target change
338 static float previousDistanceToHomeCm
= 0.0f
; // to check that we are returning
339 static int8_t secondsLowSats
= 0; // Minimum sat detection
340 static int8_t secondsDoingNothing
; // Limit on doing nothing
341 const timeUs_t currentTimeUs
= micros();
343 if (rescueState
.phase
== RESCUE_IDLE
) {
344 rescueState
.failure
= RESCUE_HEALTHY
;
346 } else if (rescueState
.phase
== RESCUE_INITIALIZE
) {
347 // Initialize these variables each time a GPS Rescue is started
348 previousTimeUs
= currentTimeUs
;
349 prevAltitudeCm
= getAltitudeCm();
350 prevTargetAltitudeCm
= rescueState
.intent
.targetAltitudeCm
;
351 previousDistanceToHomeCm
= rescueState
.sensor
.distanceToHomeCm
;
353 secondsDoingNothing
= 0;
356 // Handle events that set a failure mode to other than healthy.
357 // Disarm via Abort when sanity on, or for hard Rx loss in FS_ONLY mode
358 // Otherwise allow 20s of semi-controlled descent with impact disarm detection
359 const bool hardFailsafe
= !isRxReceivingSignal();
361 if (rescueState
.failure
!= RESCUE_HEALTHY
) {
362 // Default to 20s semi-controlled descent with impact detection, then abort
363 rescueState
.phase
= RESCUE_DO_NOTHING
;
365 switch(gpsRescueConfig()->sanityChecks
) {
366 case RESCUE_SANITY_ON
:
367 rescueState
.phase
= RESCUE_ABORT
;
369 case RESCUE_SANITY_FS_ONLY
:
371 rescueState
.phase
= RESCUE_ABORT
;
375 // even with sanity checks off,
376 // override when Allow Arming without Fix is enabled without GPS_FIX_HOME and no Control link available.
377 if (gpsRescueConfig()->allowArmingWithoutFix
&& !STATE(GPS_FIX_HOME
) && hardFailsafe
) {
378 rescueState
.phase
= RESCUE_ABORT
;
383 // Crash detection is enabled in all rescues. If triggered, immediately disarm.
384 if (crashRecoveryModeActive()) {
385 setArmingDisabled(ARMING_DISABLED_ARM_SWITCH
);
386 disarm(DISARM_REASON_CRASH_PROTECTION
);
390 // Check if GPS comms are healthy
391 // ToDo - check if we have an altitude reading; if we have Baro, we can use Landing mode for controlled descent without GPS
392 if (!rescueState
.sensor
.healthy
) {
393 rescueState
.failure
= RESCUE_GPSLOST
;
396 // Things that should run at a low refresh rate (such as flyaway detection, etc) will be checked at 1Hz
397 const timeDelta_t dTime
= cmpTimeUs(currentTimeUs
, previousTimeUs
);
398 if (dTime
< 1000000) { //1hz
401 previousTimeUs
= currentTimeUs
;
403 // checks that we are getting closer to home.
404 // if the quad is stuck, or if GPS data packets stop, there will be no change in distance to home
405 // we can't use rescueState.sensor.currentVelocity because it will be held at the last good value if GPS data updates stop
406 if (rescueState
.phase
== RESCUE_FLY_HOME
) {
407 const float velocityToHomeCmS
= previousDistanceToHomeCm
- rescueState
.sensor
.distanceToHomeCm
; // cm/s
408 previousDistanceToHomeCm
= rescueState
.sensor
.distanceToHomeCm
;
409 rescueState
.intent
.secondsFailing
+= (velocityToHomeCmS
< 0.1f
* rescueState
.intent
.targetVelocityCmS
) ? 1 : -1;
410 rescueState
.intent
.secondsFailing
= constrain(rescueState
.intent
.secondsFailing
, 0, 30);
411 if (rescueState
.intent
.secondsFailing
>= 30) {
413 //If there is a mag and has not been disabled, we have to assume is healthy and has been used in imu.c
414 if (sensors(SENSOR_MAG
) && gpsRescueConfig()->useMag
&& !magForceDisable
) {
415 //Try again with mag disabled
416 magForceDisable
= true;
417 rescueState
.intent
.secondsFailing
= 0;
421 rescueState
.failure
= RESCUE_FLYAWAY
;
426 secondsLowSats
+= (!STATE(GPS_FIX
) || (gpsSol
.numSat
< GPS_MIN_SAT_COUNT
)) ? 1 : -1;
427 secondsLowSats
= constrain(secondsLowSats
, 0, 10);
429 if (secondsLowSats
== 10) {
430 rescueState
.failure
= RESCUE_LOWSATS
;
433 // These conditions ignore sanity mode settings, and apply in all rescues, to handle getting stuck in a climb or descend
435 const float actualAltitudeChange
= getAltitudeCm() - prevAltitudeCm
;
436 // ** possibly could use getAltitudeDerivative() for for actual altitude change, though it is smoothed
437 const float targetAltitudeChange
= rescueState
.intent
.targetAltitudeCm
- prevTargetAltitudeCm
;
438 const float ratio
= actualAltitudeChange
/ targetAltitudeChange
;
439 prevAltitudeCm
= getAltitudeCm();
440 prevTargetAltitudeCm
= rescueState
.intent
.targetAltitudeCm
;
442 switch (rescueState
.phase
) {
444 rescueState
.intent
.secondsFailing
+= ratio
> 0.5f
? -1 : 1;
445 rescueState
.intent
.secondsFailing
= constrain(rescueState
.intent
.secondsFailing
, 0, 10);
446 if (rescueState
.intent
.secondsFailing
>= 10) {
447 rescueState
.phase
= RESCUE_ABORT
;
448 // Landing mode shouldn't take more than 10s
451 case RESCUE_ATTAIN_ALT
:
453 rescueState
.intent
.secondsFailing
+= ratio
> 0.5f
? -1 : 1;
454 rescueState
.intent
.secondsFailing
= constrain(rescueState
.intent
.secondsFailing
, 0, 10);
455 if (rescueState
.intent
.secondsFailing
>= 10) {
456 rescueState
.phase
= RESCUE_LANDING
;
457 rescueState
.intent
.secondsFailing
= 0;
458 // if can't climb, or slow descending, enable impact detection and time out in 10s
461 case RESCUE_DO_NOTHING
:
462 secondsDoingNothing
= MIN(secondsDoingNothing
+ 1, 20);
463 if (secondsDoingNothing
>= 20) {
464 rescueState
.phase
= RESCUE_ABORT
;
465 // time-limited semi-controlled fall with impact detection
473 DEBUG_SET(DEBUG_RTH
, 2, (rescueState
.failure
* 10 + rescueState
.phase
));
474 DEBUG_SET(DEBUG_RTH
, 3, (rescueState
.intent
.secondsFailing
* 100 + secondsLowSats
));
477 static void sensorUpdate(bool newGpsData
)
479 static float prevDistanceToHomeCm
= 0.0f
;
481 const float altitudeCurrentCm
= getAltitudeCm();
482 DEBUG_SET(DEBUG_GPS_RESCUE_TRACKING
, 2, lrintf(altitudeCurrentCm
));
483 DEBUG_SET(DEBUG_GPS_RESCUE_HEADING
, 0, rescueState
.sensor
.groundSpeedCmS
); // groundspeed cm/s
484 DEBUG_SET(DEBUG_GPS_RESCUE_HEADING
, 1, gpsSol
.groundCourse
); // degrees * 10
485 DEBUG_SET(DEBUG_GPS_RESCUE_HEADING
, 2, attitude
.values
.yaw
); // degrees * 10
486 DEBUG_SET(DEBUG_GPS_RESCUE_HEADING
, 3, rescueState
.sensor
.directionToHome
); // computed from current GPS position in relation to home
487 rescueState
.sensor
.healthy
= gpsIsHealthy();
489 rescueState
.sensor
.directionToHome
= GPS_directionToHome
; // extern value from gps.c using current position relative to home
490 rescueState
.sensor
.errorAngle
= (attitude
.values
.yaw
- rescueState
.sensor
.directionToHome
) / 10.0f
;
491 // both attitude and direction are in degrees * 10, errorAngle is degrees
492 if (rescueState
.sensor
.errorAngle
<= -180) {
493 rescueState
.sensor
.errorAngle
+= 360;
494 } else if (rescueState
.sensor
.errorAngle
> 180) {
495 rescueState
.sensor
.errorAngle
-= 360;
497 rescueState
.sensor
.absErrorAngle
= fabsf(rescueState
.sensor
.errorAngle
);
499 DEBUG_SET(DEBUG_GPS_RESCUE_TRACKING
, 4, lrintf(attitude
.values
.yaw
)); // estimated heading of the quad (direction nose is pointing in)
500 DEBUG_SET(DEBUG_GPS_RESCUE_TRACKING
, 5, lrintf(rescueState
.sensor
.directionToHome
)); // angle to home derived from GPS location and home position
504 // GPS ground speed, velocity and distance to home will be held at last good values if no new packets
507 rescueState
.sensor
.distanceToHomeCm
= GPS_distanceToHomeCm
;
508 rescueState
.sensor
.distanceToHomeM
= rescueState
.sensor
.distanceToHomeCm
/ 100.0f
;
509 rescueState
.sensor
.groundSpeedCmS
= gpsSol
.groundSpeed
; // cm/s
511 rescueState
.sensor
.gpsDataIntervalSeconds
= getGpsDataIntervalSeconds();
512 // Range from 50ms (20hz) to 2500ms (0.4Hz). Intended to cover common GPS data rates and exclude unusual values.
514 rescueState
.sensor
.velocityToHomeCmS
= ((prevDistanceToHomeCm
- rescueState
.sensor
.distanceToHomeCm
) * getGpsDataFrequencyHz());
515 // positive = towards home. First value is useless since prevDistanceToHomeCm was zero.
516 prevDistanceToHomeCm
= rescueState
.sensor
.distanceToHomeCm
;
518 DEBUG_SET(DEBUG_ATTITUDE
, 4, rescueState
.sensor
.velocityToHomeCmS
); // velocity to home
520 // when there is a flyaway due to IMU disorientation, increase IMU yaw CoG gain, and reduce max pitch angle
521 if (gpsRescueConfig()->groundSpeedCmS
) {
522 // calculate a factor that can reduce pitch angle when flying away
523 const float rescueGroundspeed
= gpsRescueConfig()->imuYawGain
* 100.0f
; // in cm/s, imuYawGain is m/s groundspeed
524 // rescueGroundspeed is effectively a normalising gain factor for the magnitude of the groundspeed error
525 // a higher value reduces groundspeedErrorRatio, making the radius wider and reducing the circling behaviour
527 const float groundspeedErrorRatio
= fabsf(rescueState
.sensor
.groundSpeedCmS
- rescueState
.sensor
.velocityToHomeCmS
) / rescueGroundspeed
;
528 // 0 if groundspeed = velocity to home, or both are zero
529 // 1 if forward velocity is zero but sideways speed is imuYawGain in m/s
530 // 2 if moving backwards at imuYawGain m/s, 4 if moving backwards at 2* imuYawGain m/s, etc
532 DEBUG_SET(DEBUG_ATTITUDE
, 5, groundspeedErrorRatio
* 100);
534 rescueState
.intent
.velocityItermAttenuator
= 4.0f
/ (groundspeedErrorRatio
+ 4.0f
);
535 // 1 if groundspeedErrorRatio = 0, falling to 2/3 if groundspeedErrorRatio = 2, 0.5 if groundspeedErrorRatio = 4, etc
536 // limit (essentially prevent) velocity iTerm accumulation whenever there is a meaningful groundspeed error
537 // this is a crude but simple way to prevent iTerm windup when recovering from an IMU error
538 // the magnitude of the effect will be less at low GPS data rates, since there will be fewer multiplications per second
539 // but for our purposes this should not matter much, our intent is to severely attenuate iTerm
540 // if, for example, we had a 90 degree attitude error, groundspeedErrorRatio = 1, invGroundspeedError = 0.8,
541 // after 10 iterations, iTerm is 0.1 of what it would have been
542 // also is useful in blocking iTerm accumulation if we overshoot the landing point
544 const float pitchForwardAngle
= (gpsRescueAngle
[AI_PITCH
] > 0.0f
) ? fminf(gpsRescueAngle
[AI_PITCH
] / 3000.0f
, 2.0f
) : 0.0f
;
545 // pitchForwardAngle is positive early in a rescue, and associates with a nose forward ground course
546 // note: gpsRescueAngle[AI_PITCH] is in degrees * 100, and is halved when the IMU is 180 wrong
547 // pitchForwardAngle is 0 when flat
548 // pitchForwardAngle is 0.5 if pitch angle is 15 degrees (ie with rescue angle of 30 and 180deg IMU error)
549 // pitchForwardAngle is 1.0 if pitch angle is 30 degrees (ie with rescue angle of 60 and 180deg IMU error)
550 // pitchForwardAngle is 2.0 if pitch angle is 60 degrees and flying towards home (unlikely to be sustained at that angle)
552 DEBUG_SET(DEBUG_ATTITUDE
, 6, pitchForwardAngle
* 100.0f
);
554 if (rescueState
.phase
!= RESCUE_FLY_HOME
) {
555 // prevent IMU disorientation arising from drift during climb, rotate or do nothing phases, which have zero pitch angle
556 // in descent, or too close, increase IMU yaw gain as pitch angle increases
557 rescueState
.sensor
.imuYawCogGain
= pitchForwardAngle
;
559 rescueState
.sensor
.imuYawCogGain
= pitchForwardAngle
+ fminf(groundspeedErrorRatio
, 3.5f
);
560 // imuYawCogGain will be more positive at higher pitch angles and higher groundspeed errors
561 // imuYawCogGain will be lowest (close to zero) at lower pitch angles and when flying straight towards home
565 DEBUG_SET(DEBUG_GPS_RESCUE_VELOCITY
, 2, lrintf(rescueState
.sensor
.velocityToHomeCmS
));
566 DEBUG_SET(DEBUG_GPS_RESCUE_TRACKING
, 0, lrintf(rescueState
.sensor
.velocityToHomeCmS
));
569 // This function flashes "RESCUE N/A" in the OSD if:
570 // 1. sensor healthy - GPS data is being received.
571 // 2. GPS has a 3D fix.
572 // 3. GPS number of satellites is greater than or equal to the minimum configured satellite count.
573 // Note 1: cannot arm without the required number of sats
574 // hence this flashing indicates that after having enough sats, we now have below the minimum and the rescue likely would fail
575 // Note 2: this function does not take into account the distance from home
576 // The sanity checks are independent, this just provides the OSD warning
577 static bool checkGPSRescueIsAvailable(void)
579 static timeUs_t previousTimeUs
= 0; // Last time LowSat was checked
580 const timeUs_t currentTimeUs
= micros();
581 static int8_t secondsLowSats
= 0; // Minimum sat detection
582 static bool lowsats
= false;
583 static bool noGPSfix
= false;
586 if (!gpsIsHealthy() || !STATE(GPS_FIX_HOME
)) {
590 // Things that should run at a low refresh rate >> ~1hz
591 const timeDelta_t dTime
= cmpTimeUs(currentTimeUs
, previousTimeUs
);
592 if (dTime
< 1000000) { //1hz
593 if (noGPSfix
|| lowsats
) {
599 previousTimeUs
= currentTimeUs
;
601 if (!STATE(GPS_FIX
)) {
608 secondsLowSats
= constrain(secondsLowSats
+ ((gpsSol
.numSat
< GPS_MIN_SAT_COUNT
) ? 1 : -1), 0, 2);
609 if (secondsLowSats
== 2) {
619 void disarmOnImpact(void)
621 if (acc
.accMagnitude
> rescueState
.intent
.disarmThreshold
) {
622 setArmingDisabled(ARMING_DISABLED_ARM_SWITCH
);
623 disarm(DISARM_REASON_GPS_RESCUE
);
628 void descend(bool newGpsData
)
631 // consider landing area to be a circle half landing height around home, to avoid overshooting home point
632 const float distanceToLandingAreaM
= rescueState
.sensor
.distanceToHomeM
- (0.5f
* apConfig()->landing_altitude_m
);
633 const float proximityToLandingArea
= constrainf(distanceToLandingAreaM
/ rescueState
.intent
.descentDistanceM
, 0.0f
, 1.0f
);
635 // increase the velocity lowpass filter cutoff for more aggressive responses when descending, especially close to home
636 // 1.5x when starting descent, 2.5x (smoother) when almost landed
637 rescueState
.intent
.velocityPidCutoffModifier
= 2.5f
- proximityToLandingArea
;
639 // reduce target velocity as we get closer to home. Zero within 2m of home, reducing risk of overshooting.
640 rescueState
.intent
.targetVelocityCmS
= gpsRescueConfig()->groundSpeedCmS
* proximityToLandingArea
;
642 // attenuate velocity target unless pointing towards home, to minimise circling behaviour during overshoots
643 if (rescueState
.sensor
.absErrorAngle
> GPS_RESCUE_ALLOWED_YAW_RANGE
) {
644 rescueState
.intent
.targetVelocityCmS
= 0;
646 rescueState
.intent
.targetVelocityCmS
*= (GPS_RESCUE_ALLOWED_YAW_RANGE
- rescueState
.sensor
.absErrorAngle
) / GPS_RESCUE_ALLOWED_YAW_RANGE
;
649 // attenuate velocity iterm towards zero as we get closer to the landing area
650 rescueState
.intent
.velocityItermAttenuator
= fminf(proximityToLandingArea
, rescueState
.intent
.velocityItermAttenuator
);
652 // full pitch angle available all the time
653 rescueState
.intent
.pitchAngleLimitDeg
= gpsRescueConfig()->maxRescueAngle
;
655 // limit roll angle to half the allowed pitch angle and attenuate when closer to home
656 // keep some roll when at the landing circle distance to avoid endless circling
657 const float proximityToHome
= constrainf(rescueState
.sensor
.distanceToHomeM
/ rescueState
.intent
.descentDistanceM
, 0.0f
, 1.0f
);
658 rescueState
.intent
.rollAngleLimitDeg
= 0.5f
* rescueState
.intent
.pitchAngleLimitDeg
* proximityToHome
;
661 // ensure we have full yaw authority in case we entered descent mode without enough time in fly home to acquire it gracefully
662 rescueState
.intent
.yawAttenuator
= 1.0f
;
664 // set the altitude step, considering the interval between altitude readings and the descent rate
665 float altitudeStepCm
= taskIntervalSeconds
* gpsRescueConfig()->descendRate
;
667 // at or below 10m: descend at 0.6x set value; above 10m, descend faster, to max 3.0x at 50m
668 altitudeStepCm
*= scaleRangef(constrainf(rescueState
.intent
.targetAltitudeCm
, 1000, 5000), 1000, 5000, 0.6f
, 3.0f
);
670 rescueState
.intent
.targetAltitudeStepCm
= -altitudeStepCm
;
671 rescueState
.intent
.targetAltitudeCm
-= altitudeStepCm
;
674 void initialiseRescueValues (void)
676 rescueState
.intent
.secondsFailing
= 0; // reset the sanity check timer
677 rescueState
.intent
.yawAttenuator
= 0.0f
; // no yaw in the climb
678 rescueState
.intent
.targetVelocityCmS
= rescueState
.sensor
.velocityToHomeCmS
; // avoid snap from D at the start
679 rescueState
.intent
.rollAngleLimitDeg
= 0.0f
; // no roll until flying home
680 rescueState
.intent
.velocityPidCutoffModifier
= 1.0f
; // normal velocity lowpass filter cutoff
681 rescueState
.intent
.pitchAngleLimitDeg
= 0.0f
; // force pitch adjustment to zero - level mode will level out
682 rescueState
.intent
.velocityItermAttenuator
= 1.0f
; // allow iTerm to accumulate normally unless constrained by IMU error or descent phase
683 rescueState
.intent
.velocityItermRelax
= 0.0f
; // but don't accumulate any at the start, not until fly home
684 rescueState
.intent
.targetAltitudeStepCm
= 0.0f
;
687 void gpsRescueUpdate(void)
688 // runs at gpsRescueTaskIntervalSeconds, and runs whether or not rescue is active
690 static uint16_t gpsStamp
= 0;
691 bool newGpsData
= gpsHasNewData(&gpsStamp
);
693 if (!FLIGHT_MODE(GPS_RESCUE_MODE
)) {
694 rescueStop(); // sets phase to RESCUE_IDLE; does nothing else. RESCUE_IDLE tasks still run.
695 } else if (FLIGHT_MODE(GPS_RESCUE_MODE
) && rescueState
.phase
== RESCUE_IDLE
) {
696 rescueStart(); // sets phase to rescue_initialise if we enter GPS Rescue mode while idle
697 rescueAttainPosition(false); // Initialise basic parameters when a Rescue starts (can't initialise sensor data reliably)
698 performSanityChecks(); // Initialises sanity check values when a Rescue starts
700 // Will now be in RESCUE_INITIALIZE mode, if just entered Rescue while IDLE, otherwise stays IDLE
702 sensorUpdate(newGpsData
); // always get latest GPS and Altitude data, update ascend and descend rates
704 static bool returnAltitudeLow
= true;
705 static bool initialVelocityLow
= true;
706 rescueState
.isAvailable
= checkGPSRescueIsAvailable();
708 switch (rescueState
.phase
) {
710 // in Idle phase = NOT in GPS Rescue
711 // update the return altitude and descent distance values, to have valid settings immediately they are needed
712 setReturnAltitude(newGpsData
);
714 // sanity checks are bypassed in IDLE mode; instead, failure state is always initialised to HEALTHY
715 // target altitude is always set to current altitude.
717 case RESCUE_INITIALIZE
:
718 // Things that should be done at the start of a Rescue
719 if (!STATE(GPS_FIX_HOME
)) {
720 // we didn't get a home point on arming
721 rescueState
.failure
= RESCUE_NO_HOME_POINT
;
722 // will result in a disarm via the sanity check system, or float around if switch induced
724 if (rescueState
.sensor
.distanceToHomeM
< 5.0f
&& isBelowLandingAltitude()) {
725 // attempted initiation within 5m of home, and 'on the ground' -> instant disarm, for safety reasons
726 rescueState
.phase
= RESCUE_ABORT
;
728 // attempted initiation within minimum rescue distance requires us to fly out to at least that distance
729 if (rescueState
.sensor
.distanceToHomeM
< gpsRescueConfig()->minStartDistM
) {
730 // climb above current height by buffer height, to at least 10m altitude
731 rescueState
.intent
.returnAltitudeCm
= fmaxf(1000.0f
, getAltitudeCm() + (gpsRescueConfig()->initialClimbM
* 100.0f
));
732 // note that the pitch controller will pitch forward to fly out to minStartDistM
733 // set the descent distance to half the minimum rescue distance. which we should have moved out to in the climb phase
734 rescueState
.intent
.descentDistanceM
= 0.5f
* gpsRescueConfig()->minStartDistM
;
736 // otherwise behave as for a normal rescue
737 initialiseRescueValues ();
738 returnAltitudeLow
= getAltitudeCm() < rescueState
.intent
.returnAltitudeCm
;
739 rescueState
.phase
= RESCUE_ATTAIN_ALT
;
744 case RESCUE_ATTAIN_ALT
:
745 // gradually increment the target altitude until the craft reaches target altitude
746 // note that this can mean the target altitude may increase above returnAltitude if the craft lags target
747 // sanity check will abort if altitude gain is blocked for a cumulative period
748 if (returnAltitudeLow
== (getAltitudeCm() < rescueState
.intent
.returnAltitudeCm
)) {
749 // we started low, and still are low; also true if we started high, and still are too high
750 rescueState
.intent
.targetAltitudeStepCm
= (returnAltitudeLow
? gpsRescueConfig()->ascendRate
: -1.0f
* gpsRescueConfig()->descendRate
) * taskIntervalSeconds
;
751 rescueState
.intent
.targetAltitudeCm
+= rescueState
.intent
.targetAltitudeStepCm
;
754 // target altitude achieved - move on to ROTATE phase, returning at target altitude
755 rescueState
.intent
.targetAltitudeCm
= rescueState
.intent
.returnAltitudeCm
;
756 rescueState
.intent
.targetAltitudeStepCm
= 0.0f
;
757 // if initiated too close, do not rotate or do anything else until sufficiently far away that a 'normal' rescue can happen
758 if (rescueState
.sensor
.distanceToHomeM
> gpsRescueConfig()->minStartDistM
) {
759 rescueState
.phase
= RESCUE_ROTATE
;
763 // give velocity P and I no error that otherwise could be present due to velocity drift at the start of the rescue
764 rescueState
.intent
.targetVelocityCmS
= rescueState
.sensor
.velocityToHomeCmS
;
768 if (rescueState
.intent
.yawAttenuator
< 1.0f
) { // acquire yaw authority over one second
769 rescueState
.intent
.yawAttenuator
+= taskIntervalSeconds
;
771 if (rescueState
.sensor
.absErrorAngle
< GPS_RESCUE_ALLOWED_YAW_RANGE
) {
772 // enter fly home phase, and enable pitch, when the yaw angle error is small enough
773 rescueState
.intent
.pitchAngleLimitDeg
= gpsRescueConfig()->maxRescueAngle
;
774 rescueState
.phase
= RESCUE_FLY_HOME
; // enter fly home phase
775 rescueState
.intent
.secondsFailing
= 0; // reset sanity timer for flight home
777 initialVelocityLow
= rescueState
.sensor
.velocityToHomeCmS
< gpsRescueConfig()->groundSpeedCmS
; // used to set direction of velocity target change
778 rescueState
.intent
.targetVelocityCmS
= rescueState
.sensor
.velocityToHomeCmS
;
781 case RESCUE_FLY_HOME
:
782 if (rescueState
.intent
.yawAttenuator
< 1.0f
) { // be sure to accumulate full yaw authority
783 rescueState
.intent
.yawAttenuator
+= taskIntervalSeconds
;
785 // velocity PIDs are now active
786 // update target velocity gradually, aiming for rescueGroundspeed with a time constant of 1.0s
787 const float targetVelocityError
= gpsRescueConfig()->groundSpeedCmS
- rescueState
.intent
.targetVelocityCmS
;
788 const float velocityTargetStep
= taskIntervalSeconds
* targetVelocityError
;
789 // velocityTargetStep is positive when starting low, negative when starting high
790 const bool targetVelocityIsLow
= rescueState
.intent
.targetVelocityCmS
< gpsRescueConfig()->groundSpeedCmS
;
791 if (initialVelocityLow
== targetVelocityIsLow
) {
792 // also true if started faster than target velocity and target is still high
793 rescueState
.intent
.targetVelocityCmS
+= velocityTargetStep
;
796 // slowly introduce velocity iTerm accumulation at start, goes 0 ->1 with time constant 2.0s
797 rescueState
.intent
.velocityItermRelax
+= 0.5f
* taskIntervalSeconds
* (1.0f
- rescueState
.intent
.velocityItermRelax
);
798 // there is always a lot of lag at the start, this gradual start avoids excess iTerm accumulation
800 rescueState
.intent
.velocityPidCutoffModifier
= 2.0f
- rescueState
.intent
.velocityItermRelax
;
801 // higher velocity filter cutoff for initial few seconds to improve accuracy; can be smoother later
804 // cut back on allowed angle if there is a high groundspeed error
805 rescueState
.intent
.pitchAngleLimitDeg
= gpsRescueConfig()->maxRescueAngle
;
806 // introduce roll slowly and limit to half the max pitch angle; earth referenced yaw may add more roll via angle code
807 rescueState
.intent
.rollAngleLimitDeg
= 0.5f
* rescueState
.intent
.pitchAngleLimitDeg
* rescueState
.intent
.velocityItermRelax
;
808 if (rescueState
.sensor
.distanceToHomeM
<= rescueState
.intent
.descentDistanceM
) {
809 rescueState
.phase
= RESCUE_DESCENT
;
810 rescueState
.intent
.secondsFailing
= 0; // reset sanity timer for descent
816 // attenuate velocity and altitude targets while updating the heading to home
817 if (isBelowLandingAltitude()) {
818 // enter landing mode once below landing altitude
819 rescueState
.phase
= RESCUE_LANDING
;
820 rescueState
.intent
.secondsFailing
= 0; // reset sanity timer for landing
826 // Reduce altitude target steadily until impact, then disarm.
827 // control yaw angle and throttle and pitch, attenuate velocity, roll and pitch iTerm
828 // increase velocity smoothing cutoff as we get closer to ground
834 setArmingDisabled(ARMING_DISABLED_ARM_SWITCH
);
835 disarm(DISARM_REASON_FAILSAFE
);
836 rescueState
.intent
.secondsFailing
= 0; // reset sanity timers so we can re-arm
840 case RESCUE_DO_NOTHING
:
848 DEBUG_SET(DEBUG_GPS_RESCUE_TRACKING
, 3, lrintf(rescueState
.intent
.targetAltitudeCm
));
849 DEBUG_SET(DEBUG_RTH
, 0, lrintf(rescueState
.intent
.maxAltitudeCm
/ 10.0f
));
851 performSanityChecks();
852 rescueAttainPosition(newGpsData
);
855 float gpsRescueGetYawRate(void)
857 return rescueYaw
; // the control yaw value for rc.c to be used while flightMode gps_rescue is active.
860 float gpsRescueGetImuYawCogGain(void)
862 return rescueState
.sensor
.imuYawCogGain
; // to speed up the IMU orientation to COG when needed
865 bool gpsRescueIsConfigured(void)
867 return failsafeConfig()->failsafe_procedure
== FAILSAFE_PROCEDURE_GPS_RESCUE
|| isModeActivationConditionPresent(BOXGPSRESCUE
);
870 bool gpsRescueIsAvailable(void)
872 return rescueState
.isAvailable
; // flashes the warning when not available (low sats, etc)
875 bool gpsRescueIsDisabled(void)
876 // used for OSD warning, needs review
878 return (!STATE(GPS_FIX_HOME
));
882 bool gpsRescueDisableMag(void)
884 // Enable mag on user request, but don't use it during fly home or if force disabled
885 // Note that while flying home the course over ground from GPS provides a heading that is less affected by wind
886 return !(gpsRescueConfig()->useMag
&& rescueState
.phase
!= RESCUE_FLY_HOME
&& !magForceDisable
);