landing tweaks
[inav.git] / src / main / navigation / navigation_multicopter.c
blob66783d8fa0f77f35717fbf7491b9def2539b4f0b
1 /*
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/>.
18 #include <stdbool.h>
19 #include <stdint.h>
20 #include <math.h>
22 #include "platform.h"
24 #include "build/build_config.h"
25 #include "build/debug.h"
27 #include "drivers/time.h"
29 #include "common/axis.h"
30 #include "common/maths.h"
31 #include "common/filter.h"
32 #include "common/utils.h"
34 #include "sensors/sensors.h"
35 #include "sensors/acceleration.h"
36 #include "sensors/boardalignment.h"
37 #include "sensors/gyro.h"
39 #include "fc/config.h"
40 #include "fc/rc_controls.h"
41 #include "fc/rc_curves.h"
42 #include "fc/rc_modes.h"
43 #include "fc/runtime_config.h"
45 #include "flight/pid.h"
46 #include "flight/imu.h"
47 #include "flight/failsafe.h"
48 #include "flight/mixer.h"
50 #include "navigation/navigation.h"
51 #include "navigation/navigation_private.h"
52 #include "navigation/sqrt_controller.h"
54 #include "sensors/battery.h"
56 /*-----------------------------------------------------------
57 * Altitude controller for multicopter aircraft
58 *-----------------------------------------------------------*/
60 static int16_t rcCommandAdjustedThrottle;
61 static int16_t altHoldThrottleRCZero = 1500;
62 static pt1Filter_t altholdThrottleFilterState;
63 static bool prepareForTakeoffOnReset = false;
64 static sqrt_controller_t alt_hold_sqrt_controller;
66 // Position to velocity controller for Z axis
67 static void updateAltitudeVelocityController_MC(timeDelta_t deltaMicros)
69 float targetVel = sqrtControllerApply(
70 &alt_hold_sqrt_controller,
71 posControl.desiredState.pos.z,
72 navGetCurrentActualPositionAndVelocity()->pos.z,
73 US2S(deltaMicros)
76 // hard limit desired target velocity to max_climb_rate
77 float vel_max_z = 0.0f;
79 if (posControl.flags.isAdjustingAltitude) {
80 vel_max_z = navConfig()->general.max_manual_climb_rate;
81 } else {
82 vel_max_z = navConfig()->general.max_auto_climb_rate;
85 targetVel = constrainf(targetVel, -vel_max_z, vel_max_z);
87 posControl.pids.pos[Z].output_constrained = targetVel;
89 // Limit max up/down acceleration target
90 const float smallVelChange = US2S(deltaMicros) * (GRAVITY_CMSS * 0.1f);
91 const float velTargetChange = targetVel - posControl.desiredState.vel.z;
93 if (velTargetChange <= -smallVelChange) {
94 // Large & Negative - acceleration is _down_. We can't reach more than -1G in any possible condition. Hard limit to 0.8G to stay safe
95 // This should be safe enough for stability since we only reduce throttle
96 const float maxVelDifference = US2S(deltaMicros) * (GRAVITY_CMSS * 0.8f);
97 posControl.desiredState.vel.z = constrainf(targetVel, posControl.desiredState.vel.z - maxVelDifference, posControl.desiredState.vel.z + maxVelDifference);
99 else if (velTargetChange >= smallVelChange) {
100 // Large and positive - acceleration is _up_. We are limited by thrust/weight ratio which is usually about 2:1 (hover around 50% throttle).
101 // T/W ratio = 2 means we are able to reach 1G acceleration in "UP" direction. Hard limit to 0.5G to be on a safe side and avoid abrupt throttle changes
102 const float maxVelDifference = US2S(deltaMicros) * (GRAVITY_CMSS * 0.5f);
103 posControl.desiredState.vel.z = constrainf(targetVel, posControl.desiredState.vel.z - maxVelDifference, posControl.desiredState.vel.z + maxVelDifference);
105 else {
106 // Small - desired acceleration is less than 0.1G. We should be safe setting velocity target directly - any platform should be able to satisfy this
107 posControl.desiredState.vel.z = targetVel;
110 navDesiredVelocity[Z] = constrain(lrintf(posControl.desiredState.vel.z), -32678, 32767);
113 static void updateAltitudeThrottleController_MC(timeDelta_t deltaMicros)
115 // Calculate min and max throttle boundaries (to compensate for integral windup)
116 const int16_t thrAdjustmentMin = (int16_t)getThrottleIdleValue() - (int16_t)currentBatteryProfile->nav.mc.hover_throttle;
117 const int16_t thrAdjustmentMax = (int16_t)motorConfig()->maxthrottle - (int16_t)currentBatteryProfile->nav.mc.hover_throttle;
119 float velocity_controller = navPidApply2(&posControl.pids.vel[Z], posControl.desiredState.vel.z, navGetCurrentActualPositionAndVelocity()->vel.z, US2S(deltaMicros), thrAdjustmentMin, thrAdjustmentMax, 0);
121 posControl.rcAdjustment[THROTTLE] = pt1FilterApply4(&altholdThrottleFilterState, velocity_controller, NAV_THROTTLE_CUTOFF_FREQENCY_HZ, US2S(deltaMicros));
123 posControl.rcAdjustment[THROTTLE] = constrain(posControl.rcAdjustment[THROTTLE], thrAdjustmentMin, thrAdjustmentMax);
125 posControl.rcAdjustment[THROTTLE] = constrain((int16_t)currentBatteryProfile->nav.mc.hover_throttle + posControl.rcAdjustment[THROTTLE], getThrottleIdleValue(), motorConfig()->maxthrottle);
128 bool adjustMulticopterAltitudeFromRCInput(void)
130 if (posControl.flags.isTerrainFollowEnabled) {
131 const float altTarget = scaleRangef(rcCommand[THROTTLE], getThrottleIdleValue(), motorConfig()->maxthrottle, 0, navConfig()->general.max_terrain_follow_altitude);
133 // In terrain follow mode we apply different logic for terrain control
134 if (posControl.flags.estAglStatus == EST_TRUSTED && altTarget > 10.0f) {
135 // We have solid terrain sensor signal - directly map throttle to altitude
136 updateClimbRateToAltitudeController(0, ROC_TO_ALT_RESET);
137 posControl.desiredState.pos.z = altTarget;
139 else {
140 updateClimbRateToAltitudeController(-50.0f, ROC_TO_ALT_NORMAL);
143 // In surface tracking we always indicate that we're adjusting altitude
144 return true;
146 else {
147 const int16_t rcThrottleAdjustment = applyDeadbandRescaled(rcCommand[THROTTLE] - altHoldThrottleRCZero, rcControlsConfig()->alt_hold_deadband, -500, 500);
148 if (rcThrottleAdjustment) {
149 // set velocity proportional to stick movement
150 float rcClimbRate;
152 // Make sure we can satisfy max_manual_climb_rate in both up and down directions
153 if (rcThrottleAdjustment > 0) {
154 // Scaling from altHoldThrottleRCZero to maxthrottle
155 rcClimbRate = rcThrottleAdjustment * navConfig()->general.max_manual_climb_rate / (float)(motorConfig()->maxthrottle - altHoldThrottleRCZero - rcControlsConfig()->alt_hold_deadband);
157 else {
158 // Scaling from minthrottle to altHoldThrottleRCZero
159 rcClimbRate = rcThrottleAdjustment * navConfig()->general.max_manual_climb_rate / (float)(altHoldThrottleRCZero - getThrottleIdleValue() - rcControlsConfig()->alt_hold_deadband);
162 updateClimbRateToAltitudeController(rcClimbRate, ROC_TO_ALT_NORMAL);
164 return true;
166 else {
167 // Adjusting finished - reset desired position to stay exactly where pilot released the stick
168 if (posControl.flags.isAdjustingAltitude) {
169 updateClimbRateToAltitudeController(0, ROC_TO_ALT_RESET);
172 return false;
177 void setupMulticopterAltitudeController(void)
179 const bool throttleIsLow = throttleStickIsLow();
181 if (navConfig()->general.flags.use_thr_mid_for_althold) {
182 altHoldThrottleRCZero = rcLookupThrottleMid();
184 else {
185 // If throttle is LOW - use Thr Mid anyway
186 if (throttleIsLow) {
187 altHoldThrottleRCZero = rcLookupThrottleMid();
189 else {
190 altHoldThrottleRCZero = rcCommand[THROTTLE];
194 // Make sure we are able to satisfy the deadband
195 altHoldThrottleRCZero = constrain(altHoldThrottleRCZero,
196 getThrottleIdleValue() + rcControlsConfig()->alt_hold_deadband + 10,
197 motorConfig()->maxthrottle - rcControlsConfig()->alt_hold_deadband - 10);
199 // Force AH controller to initialize althold integral for pending takeoff on reset
200 // Signal for that is low throttle _and_ low actual altitude
201 if (throttleIsLow && fabsf(navGetCurrentActualPositionAndVelocity()->pos.z) <= 50.0f) {
202 prepareForTakeoffOnReset = true;
206 void resetMulticopterAltitudeController(void)
208 const navEstimatedPosVel_t *posToUse = navGetCurrentActualPositionAndVelocity();
209 float nav_speed_up = 0.0f;
210 float nav_speed_down = 0.0f;
211 float nav_accel_z = 0.0f;
213 navPidReset(&posControl.pids.vel[Z]);
214 navPidReset(&posControl.pids.surface);
216 posControl.rcAdjustment[THROTTLE] = 0;
218 posControl.desiredState.vel.z = posToUse->vel.z; // Gradually transition from current climb
220 pt1FilterReset(&altholdThrottleFilterState, 0.0f);
221 pt1FilterReset(&posControl.pids.vel[Z].error_filter_state, 0.0f);
222 pt1FilterReset(&posControl.pids.vel[Z].dterm_filter_state, 0.0f);
224 if (FLIGHT_MODE(FAILSAFE_MODE) || FLIGHT_MODE(NAV_RTH_MODE) || FLIGHT_MODE(NAV_WP_MODE) || navigationIsExecutingAnEmergencyLanding()) {
225 const float maxSpeed = getActiveWaypointSpeed();
226 nav_speed_up = maxSpeed;
227 nav_accel_z = maxSpeed;
228 nav_speed_down = navConfig()->general.max_auto_climb_rate;
229 } else {
230 nav_speed_up = navConfig()->general.max_manual_speed;
231 nav_accel_z = navConfig()->general.max_manual_speed;
232 nav_speed_down = navConfig()->general.max_manual_climb_rate;
235 sqrtControllerInit(
236 &alt_hold_sqrt_controller,
237 posControl.pids.pos[Z].param.kP,
238 -fabsf(nav_speed_down),
239 nav_speed_up,
240 nav_accel_z
244 static void applyMulticopterAltitudeController(timeUs_t currentTimeUs)
246 static timeUs_t previousTimePositionUpdate = 0; // Occurs @ altitude sensor update rate (max MAX_ALTITUDE_UPDATE_RATE_HZ)
248 // If we have an update on vertical position data - update velocity and accel targets
249 if (posControl.flags.verticalPositionDataNew) {
250 const timeDeltaLarge_t deltaMicrosPositionUpdate = currentTimeUs - previousTimePositionUpdate;
251 previousTimePositionUpdate = currentTimeUs;
253 // Check if last correction was not too long ago
254 if (deltaMicrosPositionUpdate < MAX_POSITION_UPDATE_INTERVAL_US) {
255 // If we are preparing for takeoff - start with lowset possible climb rate, adjust alt target and make sure throttle doesn't jump
256 if (prepareForTakeoffOnReset) {
257 const navEstimatedPosVel_t *posToUse = navGetCurrentActualPositionAndVelocity();
259 posControl.desiredState.vel.z = -navConfig()->general.max_manual_climb_rate;
260 posControl.desiredState.pos.z = posToUse->pos.z - (navConfig()->general.max_manual_climb_rate / posControl.pids.pos[Z].param.kP);
261 posControl.pids.vel[Z].integrator = -500.0f;
262 pt1FilterReset(&altholdThrottleFilterState, -500.0f);
263 prepareForTakeoffOnReset = false;
266 // Execute actual altitude controllers
267 updateAltitudeVelocityController_MC(deltaMicrosPositionUpdate);
268 updateAltitudeThrottleController_MC(deltaMicrosPositionUpdate);
270 else {
271 // Position update has not occurred in time (first start or glitch), reset altitude controller
272 resetMulticopterAltitudeController();
275 // Indicate that information is no longer usable
276 posControl.flags.verticalPositionDataConsumed = true;
279 // Update throttle controller
280 rcCommand[THROTTLE] = posControl.rcAdjustment[THROTTLE];
282 // Save processed throttle for future use
283 rcCommandAdjustedThrottle = rcCommand[THROTTLE];
286 /*-----------------------------------------------------------
287 * Adjusts desired heading from pilot's input
288 *-----------------------------------------------------------*/
289 bool adjustMulticopterHeadingFromRCInput(void)
291 if (ABS(rcCommand[YAW]) > rcControlsConfig()->pos_hold_deadband) {
292 // Can only allow pilot to set the new heading if doing PH, during RTH copter will target itself to home
293 posControl.desiredState.yaw = posControl.actualState.yaw;
295 return true;
297 else {
298 return false;
302 /*-----------------------------------------------------------
303 * XY-position controller for multicopter aircraft
304 *-----------------------------------------------------------*/
305 static float lastAccelTargetX = 0.0f, lastAccelTargetY = 0.0f;
307 void resetMulticopterBrakingMode(void)
309 DISABLE_STATE(NAV_CRUISE_BRAKING);
310 DISABLE_STATE(NAV_CRUISE_BRAKING_BOOST);
311 DISABLE_STATE(NAV_CRUISE_BRAKING_LOCKED);
314 static void processMulticopterBrakingMode(const bool isAdjusting)
316 #ifdef USE_MR_BRAKING_MODE
317 static uint32_t brakingModeDisengageAt = 0;
318 static uint32_t brakingBoostModeDisengageAt = 0;
320 if (!(NAV_Status.state == MW_NAV_STATE_NONE || NAV_Status.state == MW_NAV_STATE_HOLD_INFINIT)) {
321 resetMulticopterBrakingMode();
322 return;
325 const bool brakingEntryAllowed =
326 IS_RC_MODE_ACTIVE(BOXBRAKING) &&
327 !STATE(NAV_CRUISE_BRAKING_LOCKED) &&
328 posControl.actualState.velXY > navConfig()->mc.braking_speed_threshold &&
329 !isAdjusting &&
330 navConfig()->general.flags.user_control_mode == NAV_GPS_CRUISE &&
331 navConfig()->mc.braking_speed_threshold > 0;
335 * Case one, when we order to brake (sticks to the center) and we are moving above threshold
336 * Speed is above 1m/s and sticks are centered
337 * Extra condition: BRAKING flight mode has to be enabled
339 if (brakingEntryAllowed) {
341 * Set currnt position and target position
342 * Enabling NAV_CRUISE_BRAKING locks other routines from setting position!
344 setDesiredPosition(&navGetCurrentActualPositionAndVelocity()->pos, 0, NAV_POS_UPDATE_XY);
346 ENABLE_STATE(NAV_CRUISE_BRAKING_LOCKED);
347 ENABLE_STATE(NAV_CRUISE_BRAKING);
349 //Set forced BRAKING disengage moment
350 brakingModeDisengageAt = millis() + navConfig()->mc.braking_timeout;
352 //If speed above threshold, start boost mode as well
353 if (posControl.actualState.velXY > navConfig()->mc.braking_boost_speed_threshold) {
354 ENABLE_STATE(NAV_CRUISE_BRAKING_BOOST);
356 brakingBoostModeDisengageAt = millis() + navConfig()->mc.braking_boost_timeout;
361 // We can enter braking only after user started to move the sticks
362 if (STATE(NAV_CRUISE_BRAKING_LOCKED) && isAdjusting) {
363 DISABLE_STATE(NAV_CRUISE_BRAKING_LOCKED);
367 * Case when speed dropped, disengage BREAKING_BOOST
369 if (
370 STATE(NAV_CRUISE_BRAKING_BOOST) && (
371 posControl.actualState.velXY <= navConfig()->mc.braking_boost_disengage_speed ||
372 brakingBoostModeDisengageAt < millis()
373 )) {
374 DISABLE_STATE(NAV_CRUISE_BRAKING_BOOST);
378 * Case when we were braking but copter finally stopped or we started to move the sticks
380 if (STATE(NAV_CRUISE_BRAKING) && (
381 posControl.actualState.velXY <= navConfig()->mc.braking_disengage_speed || //We stopped
382 isAdjusting || //Moved the sticks
383 brakingModeDisengageAt < millis() //Braking is done to timed disengage
384 )) {
385 DISABLE_STATE(NAV_CRUISE_BRAKING);
386 DISABLE_STATE(NAV_CRUISE_BRAKING_BOOST);
389 * When braking is done, store current position as desired one
390 * We do not want to go back to the place where braking has started
392 setDesiredPosition(&navGetCurrentActualPositionAndVelocity()->pos, 0, NAV_POS_UPDATE_XY);
394 #else
395 UNUSED(isAdjusting);
396 #endif
399 void resetMulticopterPositionController(void)
401 for (int axis = 0; axis < 2; axis++) {
402 navPidReset(&posControl.pids.vel[axis]);
403 posControl.rcAdjustment[axis] = 0;
404 lastAccelTargetX = 0.0f;
405 lastAccelTargetY = 0.0f;
409 bool adjustMulticopterPositionFromRCInput(int16_t rcPitchAdjustment, int16_t rcRollAdjustment)
411 // Process braking mode
412 processMulticopterBrakingMode(rcPitchAdjustment || rcRollAdjustment);
414 // Actually change position
415 if (rcPitchAdjustment || rcRollAdjustment) {
416 // If mode is GPS_CRUISE, move target position, otherwise POS controller will passthru the RC input to ANGLE PID
417 if (navConfig()->general.flags.user_control_mode == NAV_GPS_CRUISE) {
418 const float rcVelX = rcPitchAdjustment * navConfig()->general.max_manual_speed / (float)(500 - rcControlsConfig()->pos_hold_deadband);
419 const float rcVelY = rcRollAdjustment * navConfig()->general.max_manual_speed / (float)(500 - rcControlsConfig()->pos_hold_deadband);
421 // Rotate these velocities from body frame to to earth frame
422 const float neuVelX = rcVelX * posControl.actualState.cosYaw - rcVelY * posControl.actualState.sinYaw;
423 const float neuVelY = rcVelX * posControl.actualState.sinYaw + rcVelY * posControl.actualState.cosYaw;
425 // Calculate new position target, so Pos-to-Vel P-controller would yield desired velocity
426 posControl.desiredState.pos.x = navGetCurrentActualPositionAndVelocity()->pos.x + (neuVelX / posControl.pids.pos[X].param.kP);
427 posControl.desiredState.pos.y = navGetCurrentActualPositionAndVelocity()->pos.y + (neuVelY / posControl.pids.pos[Y].param.kP);
430 return true;
432 else {
433 // Adjusting finished - reset desired position to stay exactly where pilot released the stick
434 if (posControl.flags.isAdjustingPosition) {
435 fpVector3_t stopPosition;
436 calculateMulticopterInitialHoldPosition(&stopPosition);
437 setDesiredPosition(&stopPosition, 0, NAV_POS_UPDATE_XY);
440 return false;
444 static float getVelocityHeadingAttenuationFactor(void)
446 // In WP mode scale velocity if heading is different from bearing
447 if (navConfig()->mc.slowDownForTurning && (navGetCurrentStateFlags() & NAV_AUTO_WP)) {
448 const int32_t headingError = constrain(wrap_18000(posControl.desiredState.yaw - posControl.actualState.yaw), -9000, 9000);
449 const float velScaling = cos_approx(CENTIDEGREES_TO_RADIANS(headingError));
451 return constrainf(velScaling * velScaling, 0.05f, 1.0f);
452 } else {
453 return 1.0f;
457 static float getVelocityExpoAttenuationFactor(float velTotal, float velMax)
459 // Calculate factor of how velocity with applied expo is different from unchanged velocity
460 const float velScale = constrainf(velTotal / velMax, 0.01f, 1.0f);
462 // navConfig()->max_speed * ((velScale * velScale * velScale) * posControl.posResponseExpo + velScale * (1 - posControl.posResponseExpo)) / velTotal;
463 // ((velScale * velScale * velScale) * posControl.posResponseExpo + velScale * (1 - posControl.posResponseExpo)) / velScale
464 // ((velScale * velScale) * posControl.posResponseExpo + (1 - posControl.posResponseExpo));
465 return 1.0f - posControl.posResponseExpo * (1.0f - (velScale * velScale)); // x^3 expo factor
468 static void updatePositionVelocityController_MC(const float maxSpeed)
470 const float posErrorX = posControl.desiredState.pos.x - navGetCurrentActualPositionAndVelocity()->pos.x;
471 const float posErrorY = posControl.desiredState.pos.y - navGetCurrentActualPositionAndVelocity()->pos.y;
473 // Calculate target velocity
474 float newVelX = posErrorX * posControl.pids.pos[X].param.kP;
475 float newVelY = posErrorY * posControl.pids.pos[Y].param.kP;
477 // Scale velocity to respect max_speed
478 float newVelTotal = calc_length_pythagorean_2D(newVelX, newVelY);
481 * We override computed speed with max speed in following cases:
482 * 1 - computed velocity is > maxSpeed
483 * 2 - in WP mission when: slowDownForTurning is OFF, we do not fly towards na last waypoint and computed speed is < maxSpeed
485 if (
486 (navGetCurrentStateFlags() & NAV_AUTO_WP &&
487 !isNavHoldPositionActive() &&
488 newVelTotal < maxSpeed &&
489 !navConfig()->mc.slowDownForTurning
490 ) || newVelTotal > maxSpeed
492 newVelX = maxSpeed * (newVelX / newVelTotal);
493 newVelY = maxSpeed * (newVelY / newVelTotal);
494 newVelTotal = maxSpeed;
497 posControl.pids.pos[X].output_constrained = newVelX;
498 posControl.pids.pos[Y].output_constrained = newVelY;
500 // Apply expo & attenuation if heading in wrong direction - turn first, accelerate later (effective only in WP mode)
501 const float velHeadFactor = getVelocityHeadingAttenuationFactor();
502 const float velExpoFactor = getVelocityExpoAttenuationFactor(newVelTotal, maxSpeed);
503 posControl.desiredState.vel.x = newVelX * velHeadFactor * velExpoFactor;
504 posControl.desiredState.vel.y = newVelY * velHeadFactor * velExpoFactor;
506 navDesiredVelocity[X] = constrain(lrintf(posControl.desiredState.vel.x), -32678, 32767);
507 navDesiredVelocity[Y] = constrain(lrintf(posControl.desiredState.vel.y), -32678, 32767);
510 static float computeNormalizedVelocity(const float value, const float maxValue)
512 return constrainf(scaleRangef(fabsf(value), 0, maxValue, 0.0f, 1.0f), 0.0f, 1.0f);
515 static float computeVelocityScale(
516 const float value,
517 const float maxValue,
518 const float attenuationFactor,
519 const float attenuationStart,
520 const float attenuationEnd
523 const float normalized = computeNormalizedVelocity(value, maxValue);
525 float scale = scaleRangef(normalized, attenuationStart, attenuationEnd, 0, attenuationFactor);
526 return constrainf(scale, 0, attenuationFactor);
529 static void updatePositionAccelController_MC(timeDelta_t deltaMicros, float maxAccelLimit, const float maxSpeed)
531 const float measurementX = navGetCurrentActualPositionAndVelocity()->vel.x;
532 const float measurementY = navGetCurrentActualPositionAndVelocity()->vel.y;
534 const float setpointX = posControl.desiredState.vel.x;
535 const float setpointY = posControl.desiredState.vel.y;
536 const float setpointXY = calc_length_pythagorean_2D(setpointX, setpointY);
538 // Calculate velocity error
539 const float velErrorX = setpointX - measurementX;
540 const float velErrorY = setpointY - measurementY;
542 // Calculate XY-acceleration limit according to velocity error limit
543 float accelLimitX, accelLimitY;
544 const float velErrorMagnitude = calc_length_pythagorean_2D(velErrorX, velErrorY);
546 if (velErrorMagnitude > 0.1f) {
547 accelLimitX = maxAccelLimit / velErrorMagnitude * fabsf(velErrorX);
548 accelLimitY = maxAccelLimit / velErrorMagnitude * fabsf(velErrorY);
549 } else {
550 accelLimitX = maxAccelLimit / 1.414213f;
551 accelLimitY = accelLimitX;
554 // Apply additional jerk limiting of 1700 cm/s^3 (~100 deg/s), almost any copter should be able to achieve this rate
555 // This will assure that we wont't saturate out LEVEL and RATE PID controller
557 float maxAccelChange = US2S(deltaMicros) * MC_POS_CONTROL_JERK_LIMIT_CMSSS;
558 //When braking, raise jerk limit even if we are not boosting acceleration
559 #ifdef USE_MR_BRAKING_MODE
560 if (STATE(NAV_CRUISE_BRAKING)) {
561 maxAccelChange = maxAccelChange * 2;
563 #endif
565 const float accelLimitXMin = constrainf(lastAccelTargetX - maxAccelChange, -accelLimitX, +accelLimitX);
566 const float accelLimitXMax = constrainf(lastAccelTargetX + maxAccelChange, -accelLimitX, +accelLimitX);
567 const float accelLimitYMin = constrainf(lastAccelTargetY - maxAccelChange, -accelLimitY, +accelLimitY);
568 const float accelLimitYMax = constrainf(lastAccelTargetY + maxAccelChange, -accelLimitY, +accelLimitY);
570 // TODO: Verify if we need jerk limiting after all
573 * This PID controller has dynamic dTerm scale. It's less active when controller
574 * is tracking setpoint at high speed. Full dTerm is required only for position hold,
575 * acceleration and deceleration
576 * Scale down dTerm with 2D speed
578 const float setpointScale = computeVelocityScale(
579 setpointXY,
580 maxSpeed,
581 multicopterPosXyCoefficients.dTermAttenuation,
582 multicopterPosXyCoefficients.dTermAttenuationStart,
583 multicopterPosXyCoefficients.dTermAttenuationEnd
585 const float measurementScale = computeVelocityScale(
586 posControl.actualState.velXY,
587 maxSpeed,
588 multicopterPosXyCoefficients.dTermAttenuation,
589 multicopterPosXyCoefficients.dTermAttenuationStart,
590 multicopterPosXyCoefficients.dTermAttenuationEnd
593 //Choose smaller attenuation factor and convert from attenuation to scale
594 const float dtermScale = 1.0f - MIN(setpointScale, measurementScale);
596 // Apply PID with output limiting and I-term anti-windup
597 // Pre-calculated accelLimit and the logic of navPidApply2 function guarantee that our newAccel won't exceed maxAccelLimit
598 // Thus we don't need to do anything else with calculated acceleration
599 float newAccelX = navPidApply3(
600 &posControl.pids.vel[X],
601 setpointX,
602 measurementX,
603 US2S(deltaMicros),
604 accelLimitXMin,
605 accelLimitXMax,
606 0, // Flags
607 1.0f, // Total gain scale
608 dtermScale // Additional dTerm scale
610 float newAccelY = navPidApply3(
611 &posControl.pids.vel[Y],
612 setpointY,
613 measurementY,
614 US2S(deltaMicros),
615 accelLimitYMin,
616 accelLimitYMax,
617 0, // Flags
618 1.0f, // Total gain scale
619 dtermScale // Additional dTerm scale
622 int32_t maxBankAngle = DEGREES_TO_DECIDEGREES(navConfig()->mc.max_bank_angle);
624 #ifdef USE_MR_BRAKING_MODE
625 //Boost required accelerations
626 if (STATE(NAV_CRUISE_BRAKING_BOOST) && multicopterPosXyCoefficients.breakingBoostFactor > 0.0f) {
628 //Scale boost factor according to speed
629 const float boostFactor = constrainf(
630 scaleRangef(
631 posControl.actualState.velXY,
632 navConfig()->mc.braking_boost_speed_threshold,
633 navConfig()->general.max_manual_speed,
634 0.0f,
635 multicopterPosXyCoefficients.breakingBoostFactor
637 0.0f,
638 multicopterPosXyCoefficients.breakingBoostFactor
641 //Boost required acceleration for harder braking
642 newAccelX = newAccelX * (1.0f + boostFactor);
643 newAccelY = newAccelY * (1.0f + boostFactor);
645 maxBankAngle = DEGREES_TO_DECIDEGREES(navConfig()->mc.braking_bank_angle);
647 #endif
649 // Save last acceleration target
650 lastAccelTargetX = newAccelX;
651 lastAccelTargetY = newAccelY;
653 // Rotate acceleration target into forward-right frame (aircraft)
654 const float accelForward = newAccelX * posControl.actualState.cosYaw + newAccelY * posControl.actualState.sinYaw;
655 const float accelRight = -newAccelX * posControl.actualState.sinYaw + newAccelY * posControl.actualState.cosYaw;
657 // Calculate banking angles
658 const float desiredPitch = atan2_approx(accelForward, GRAVITY_CMSS);
659 const float desiredRoll = atan2_approx(accelRight * cos_approx(desiredPitch), GRAVITY_CMSS);
661 posControl.rcAdjustment[ROLL] = constrain(RADIANS_TO_DECIDEGREES(desiredRoll), -maxBankAngle, maxBankAngle);
662 posControl.rcAdjustment[PITCH] = constrain(RADIANS_TO_DECIDEGREES(desiredPitch), -maxBankAngle, maxBankAngle);
665 static void applyMulticopterPositionController(timeUs_t currentTimeUs)
667 static timeUs_t previousTimePositionUpdate = 0; // Occurs @ GPS update rate
668 bool bypassPositionController;
670 // We should passthrough rcCommand is adjusting position in GPS_ATTI mode
671 bypassPositionController = (navConfig()->general.flags.user_control_mode == NAV_GPS_ATTI) && posControl.flags.isAdjustingPosition;
673 // Apply controller only if position source is valid. In absence of valid pos sensor (GPS loss), we'd stick in forced ANGLE mode
674 // and pilots input would be passed thru to PID controller
675 if ((posControl.flags.estPosStatus >= EST_USABLE)) {
676 // If we have new position - update velocity and acceleration controllers
677 if (posControl.flags.horizontalPositionDataNew) {
678 const timeDeltaLarge_t deltaMicrosPositionUpdate = currentTimeUs - previousTimePositionUpdate;
679 previousTimePositionUpdate = currentTimeUs;
681 if (!bypassPositionController) {
682 // Update position controller
683 if (deltaMicrosPositionUpdate < MAX_POSITION_UPDATE_INTERVAL_US) {
684 // Get max speed from generic NAV (waypoint specific), don't allow to move slower than 0.5 m/s
685 const float maxSpeed = getActiveWaypointSpeed();
686 updatePositionVelocityController_MC(maxSpeed);
687 updatePositionAccelController_MC(deltaMicrosPositionUpdate, NAV_ACCELERATION_XY_MAX, maxSpeed);
689 else {
690 // Position update has not occurred in time (first start or glitch), reset altitude controller
691 resetMulticopterPositionController();
695 // Indicate that information is no longer usable
696 posControl.flags.horizontalPositionDataConsumed = true;
699 else {
700 /* No position data, disable automatic adjustment, rcCommand passthrough */
701 posControl.rcAdjustment[PITCH] = 0;
702 posControl.rcAdjustment[ROLL] = 0;
703 bypassPositionController = true;
706 if (!bypassPositionController) {
707 rcCommand[PITCH] = pidAngleToRcCommand(posControl.rcAdjustment[PITCH], pidProfile()->max_angle_inclination[FD_PITCH]);
708 rcCommand[ROLL] = pidAngleToRcCommand(posControl.rcAdjustment[ROLL], pidProfile()->max_angle_inclination[FD_ROLL]);
712 bool isMulticopterFlying(void)
714 bool throttleCondition = rcCommand[THROTTLE] > currentBatteryProfile->nav.mc.hover_throttle;
715 bool gyroCondition = averageAbsGyroRates() > 7.0f;
717 return throttleCondition && gyroCondition;
720 /*-----------------------------------------------------------
721 * Multicopter land detector
722 *-----------------------------------------------------------*/
723 bool isMulticopterLandingDetected(void)
725 DEBUG_SET(DEBUG_LANDING, 4, 0);
726 static timeUs_t landingDetectorStartedAt;
728 /* Basic condition to start looking for landing
729 * Prevent landing detection if WP mission allowed during Failsafe (except landing states) */
730 bool startCondition = (navGetCurrentStateFlags() & (NAV_CTL_LAND | NAV_CTL_EMERG))
731 || (FLIGHT_MODE(FAILSAFE_MODE) && !FLIGHT_MODE(NAV_WP_MODE))
732 || (!navigationIsFlyingAutonomousMode() && throttleStickIsLow());
734 if (!startCondition || posControl.flags.resetLandingDetector) {
735 landingDetectorStartedAt = 0;
736 return posControl.flags.resetLandingDetector = false;
739 const float sensitivity = navConfig()->general.land_detect_sensitivity / 5.0f;
741 // check vertical and horizontal velocities are low (cm/s)
742 bool velCondition = fabsf(navGetCurrentActualPositionAndVelocity()->vel.z) < (MC_LAND_CHECK_VEL_Z_MOVING * sensitivity) &&
743 posControl.actualState.velXY < (MC_LAND_CHECK_VEL_XY_MOVING * sensitivity);
744 // check gyro rates are low (degs/s)
745 bool gyroCondition = averageAbsGyroRates() < (4.0f * sensitivity);
746 DEBUG_SET(DEBUG_LANDING, 2, velCondition);
747 DEBUG_SET(DEBUG_LANDING, 3, gyroCondition);
749 bool possibleLandingDetected = false;
750 const timeUs_t currentTimeUs = micros();
752 if (navGetCurrentStateFlags() & NAV_CTL_LAND) {
753 // We have likely landed if throttle is 40 units below average descend throttle
754 // We use rcCommandAdjustedThrottle to keep track of NAV corrected throttle (isLandingDetected is executed
755 // from processRx() and rcCommand at that moment holds rc input, not adjusted values from NAV core)
756 DEBUG_SET(DEBUG_LANDING, 4, 1);
758 static int32_t landingThrSum;
759 static int32_t landingThrSamples;
760 bool isAtMinimalThrust = false;
762 if (!landingDetectorStartedAt) {
763 landingThrSum = landingThrSamples = 0;
764 landingDetectorStartedAt = currentTimeUs;
766 if (!landingThrSamples) {
767 if (currentTimeUs - landingDetectorStartedAt < (USECS_PER_SEC * MC_LAND_THR_STABILISE_DELAY)) { // Wait for 1 second so throttle has stabilized.
768 return false;
769 } else {
770 landingDetectorStartedAt = currentTimeUs;
773 landingThrSamples += 1;
774 landingThrSum += rcCommandAdjustedThrottle;
775 isAtMinimalThrust = rcCommandAdjustedThrottle < (landingThrSum / landingThrSamples - MC_LAND_DESCEND_THROTTLE);
777 possibleLandingDetected = isAtMinimalThrust && velCondition;
779 DEBUG_SET(DEBUG_LANDING, 6, rcCommandAdjustedThrottle);
780 DEBUG_SET(DEBUG_LANDING, 7, landingThrSum / landingThrSamples - MC_LAND_DESCEND_THROTTLE);
781 } else { // non autonomous and emergency landing
782 DEBUG_SET(DEBUG_LANDING, 4, 2);
783 if (landingDetectorStartedAt) {
784 possibleLandingDetected = velCondition && gyroCondition;
785 } else {
786 landingDetectorStartedAt = currentTimeUs;
787 return false;
791 // If we have surface sensor (for example sonar) - use it to detect touchdown
792 if ((posControl.flags.estAglStatus == EST_TRUSTED) && (posControl.actualState.agl.pos.z >= 0)) {
793 // TODO: Come up with a clever way to let sonar increase detection performance, not just add extra safety.
794 // TODO: Out of range sonar may give reading that looks like we landed, find a way to check if sonar is healthy.
795 // surfaceMin is our ground reference. If we are less than 5cm above the ground - we are likely landed
796 possibleLandingDetected = possibleLandingDetected && (posControl.actualState.agl.pos.z <= (posControl.actualState.surfaceMin + MC_LAND_SAFE_SURFACE));
798 DEBUG_SET(DEBUG_LANDING, 5, possibleLandingDetected);
800 if (possibleLandingDetected) {
801 timeUs_t safetyTimeDelay = MS2US(1000 + navConfig()->general.auto_disarm_delay); // check conditions stable for 1s + optional extra delay
802 return (currentTimeUs - landingDetectorStartedAt > safetyTimeDelay);
803 } else {
804 landingDetectorStartedAt = currentTimeUs;
805 return false;
809 /*-----------------------------------------------------------
810 * Multicopter emergency landing
811 *-----------------------------------------------------------*/
812 static void applyMulticopterEmergencyLandingController(timeUs_t currentTimeUs)
814 static timeUs_t previousTimePositionUpdate = 0;
816 /* Attempt to stabilise */
817 rcCommand[ROLL] = 0;
818 rcCommand[PITCH] = 0;
819 rcCommand[YAW] = 0;
821 if ((posControl.flags.estAltStatus < EST_USABLE)) {
822 /* Sensors has gone haywire, attempt to land regardless */
823 if (failsafeConfig()->failsafe_procedure == FAILSAFE_PROCEDURE_DROP_IT) {
824 rcCommand[THROTTLE] = getThrottleIdleValue();
826 else {
827 rcCommand[THROTTLE] = currentBatteryProfile->failsafe_throttle;
830 return;
833 // Normal sensor data
834 if (posControl.flags.verticalPositionDataNew) {
835 const timeDeltaLarge_t deltaMicrosPositionUpdate = currentTimeUs - previousTimePositionUpdate;
836 previousTimePositionUpdate = currentTimeUs;
838 // Check if last correction was not too long ago
839 if (deltaMicrosPositionUpdate < MAX_POSITION_UPDATE_INTERVAL_US) {
840 updateClimbRateToAltitudeController(-1.0f * navConfig()->general.emerg_descent_rate, ROC_TO_ALT_NORMAL);
841 updateAltitudeVelocityController_MC(deltaMicrosPositionUpdate);
842 updateAltitudeThrottleController_MC(deltaMicrosPositionUpdate);
844 else {
845 // due to some glitch position update has not occurred in time, reset altitude controller
846 resetMulticopterAltitudeController();
849 // Indicate that information is no longer usable
850 posControl.flags.verticalPositionDataConsumed = true;
853 // Update throttle controller
854 rcCommand[THROTTLE] = posControl.rcAdjustment[THROTTLE];
857 /*-----------------------------------------------------------
858 * Calculate loiter target based on current position and velocity
859 *-----------------------------------------------------------*/
860 void calculateMulticopterInitialHoldPosition(fpVector3_t * pos)
862 const float stoppingDistanceX = navGetCurrentActualPositionAndVelocity()->vel.x * posControl.posDecelerationTime;
863 const float stoppingDistanceY = navGetCurrentActualPositionAndVelocity()->vel.y * posControl.posDecelerationTime;
865 pos->x = navGetCurrentActualPositionAndVelocity()->pos.x + stoppingDistanceX;
866 pos->y = navGetCurrentActualPositionAndVelocity()->pos.y + stoppingDistanceY;
869 void resetMulticopterHeadingController(void)
871 updateHeadingHoldTarget(CENTIDEGREES_TO_DEGREES(posControl.actualState.yaw));
874 static void applyMulticopterHeadingController(void)
876 updateHeadingHoldTarget(CENTIDEGREES_TO_DEGREES(posControl.desiredState.yaw));
879 void applyMulticopterNavigationController(navigationFSMStateFlags_t navStateFlags, timeUs_t currentTimeUs)
881 if (navStateFlags & NAV_CTL_EMERG) {
882 applyMulticopterEmergencyLandingController(currentTimeUs);
884 else {
885 if (navStateFlags & NAV_CTL_ALT)
886 applyMulticopterAltitudeController(currentTimeUs);
888 if (navStateFlags & NAV_CTL_POS)
889 applyMulticopterPositionController(currentTimeUs);
891 if (navStateFlags & NAV_CTL_YAW)
892 applyMulticopterHeadingController();