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/>.
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/fc_core.h"
40 #include "fc/config.h"
41 #include "fc/rc_controls.h"
42 #include "fc/rc_curves.h"
43 #include "fc/rc_modes.h"
44 #include "fc/runtime_config.h"
46 #include "flight/pid.h"
47 #include "flight/imu.h"
48 #include "flight/failsafe.h"
49 #include "flight/mixer.h"
51 #include "navigation/navigation.h"
52 #include "navigation/navigation_private.h"
53 #include "navigation/sqrt_controller.h"
55 #include "sensors/battery.h"
57 /*-----------------------------------------------------------
58 * Altitude controller for multicopter aircraft
59 *-----------------------------------------------------------*/
61 static int16_t rcCommandAdjustedThrottle
;
62 static int16_t altHoldThrottleRCZero
= 1500;
63 static pt1Filter_t altholdThrottleFilterState
;
64 static bool prepareForTakeoffOnReset
= false;
65 static sqrt_controller_t alt_hold_sqrt_controller
;
67 float getSqrtControllerVelocity(float targetAltitude
, timeDelta_t deltaMicros
)
69 return sqrtControllerApply(
70 &alt_hold_sqrt_controller
,
72 navGetCurrentActualPositionAndVelocity()->pos
.z
,
77 // Position to velocity controller for Z axis
78 static void updateAltitudeVelocityController_MC(timeDelta_t deltaMicros
)
80 float targetVel
= getDesiredClimbRate(posControl
.desiredState
.pos
.z
, deltaMicros
);
82 posControl
.pids
.pos
[Z
].output_constrained
= targetVel
; // only used for Blackbox and OSD info
84 // Limit max up/down acceleration target
85 const float smallVelChange
= US2S(deltaMicros
) * (GRAVITY_CMSS
* 0.1f
);
86 const float velTargetChange
= targetVel
- posControl
.desiredState
.vel
.z
;
88 if (velTargetChange
<= -smallVelChange
) {
89 // Large & Negative - acceleration is _down_. We can't reach more than -1G in any possible condition. Hard limit to 0.8G to stay safe
90 // This should be safe enough for stability since we only reduce throttle
91 const float maxVelDifference
= US2S(deltaMicros
) * (GRAVITY_CMSS
* 0.8f
);
92 posControl
.desiredState
.vel
.z
= constrainf(targetVel
, posControl
.desiredState
.vel
.z
- maxVelDifference
, posControl
.desiredState
.vel
.z
+ maxVelDifference
);
94 else if (velTargetChange
>= smallVelChange
) {
95 // Large and positive - acceleration is _up_. We are limited by thrust/weight ratio which is usually about 2:1 (hover around 50% throttle).
96 // 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
97 const float maxVelDifference
= US2S(deltaMicros
) * (GRAVITY_CMSS
* 0.5f
);
98 posControl
.desiredState
.vel
.z
= constrainf(targetVel
, posControl
.desiredState
.vel
.z
- maxVelDifference
, posControl
.desiredState
.vel
.z
+ maxVelDifference
);
101 // Small - desired acceleration is less than 0.1G. We should be safe setting velocity target directly - any platform should be able to satisfy this
102 posControl
.desiredState
.vel
.z
= targetVel
;
105 navDesiredVelocity
[Z
] = constrain(lrintf(posControl
.desiredState
.vel
.z
), -32678, 32767);
108 static void updateAltitudeThrottleController_MC(timeDelta_t deltaMicros
)
110 // Calculate min and max throttle boundaries (to compensate for integral windup)
111 const int16_t thrCorrectionMin
= getThrottleIdleValue() - currentBatteryProfile
->nav
.mc
.hover_throttle
;
112 const int16_t thrCorrectionMax
= getMaxThrottle() - currentBatteryProfile
->nav
.mc
.hover_throttle
;
114 float velocity_controller
= navPidApply2(&posControl
.pids
.vel
[Z
], posControl
.desiredState
.vel
.z
, navGetCurrentActualPositionAndVelocity()->vel
.z
, US2S(deltaMicros
), thrCorrectionMin
, thrCorrectionMax
, 0);
116 int16_t rcThrottleCorrection
= pt1FilterApply4(&altholdThrottleFilterState
, velocity_controller
, NAV_THROTTLE_CUTOFF_FREQENCY_HZ
, US2S(deltaMicros
));
117 rcThrottleCorrection
= constrain(rcThrottleCorrection
, thrCorrectionMin
, thrCorrectionMax
);
119 posControl
.rcAdjustment
[THROTTLE
] = setDesiredThrottle(currentBatteryProfile
->nav
.mc
.hover_throttle
+ rcThrottleCorrection
, false);
122 bool adjustMulticopterAltitudeFromRCInput(void)
124 if (posControl
.flags
.isTerrainFollowEnabled
) {
125 const float altTarget
= scaleRangef(rcCommand
[THROTTLE
], getThrottleIdleValue(), getMaxThrottle(), 0, navConfig()->general
.max_terrain_follow_altitude
);
127 // In terrain follow mode we apply different logic for terrain control
128 if (posControl
.flags
.estAglStatus
== EST_TRUSTED
&& altTarget
> 10.0f
) {
129 // We have solid terrain sensor signal - directly map throttle to altitude
130 updateClimbRateToAltitudeController(0, altTarget
, ROC_TO_ALT_TARGET
);
133 updateClimbRateToAltitudeController(-50.0f
, 0, ROC_TO_ALT_CONSTANT
);
136 // In surface tracking we always indicate that we're adjusting altitude
140 const int16_t rcThrottleAdjustment
= applyDeadbandRescaled(rcCommand
[THROTTLE
] - altHoldThrottleRCZero
, rcControlsConfig()->alt_hold_deadband
, -500, 500);
142 if (rcThrottleAdjustment
) {
143 // set velocity proportional to stick movement
146 // Make sure we can satisfy max_manual_climb_rate in both up and down directions
147 if (rcThrottleAdjustment
> 0) {
148 // Scaling from altHoldThrottleRCZero to maxthrottle
149 rcClimbRate
= rcThrottleAdjustment
* navConfig()->mc
.max_manual_climb_rate
/ (float)(getMaxThrottle() - altHoldThrottleRCZero
- rcControlsConfig()->alt_hold_deadband
);
152 // Scaling from minthrottle to altHoldThrottleRCZero
153 rcClimbRate
= rcThrottleAdjustment
* navConfig()->mc
.max_manual_climb_rate
/ (float)(altHoldThrottleRCZero
- getThrottleIdleValue() - rcControlsConfig()->alt_hold_deadband
);
156 updateClimbRateToAltitudeController(rcClimbRate
, 0, ROC_TO_ALT_CONSTANT
);
161 // Adjusting finished - reset desired position to stay exactly where pilot released the stick
162 if (posControl
.flags
.isAdjustingAltitude
) {
163 updateClimbRateToAltitudeController(0, 0, ROC_TO_ALT_CURRENT
);
171 void setupMulticopterAltitudeController(void)
173 const bool throttleIsLow
= throttleStickIsLow();
174 const uint8_t throttleType
= navConfig()->mc
.althold_throttle_type
;
176 if (throttleType
== MC_ALT_HOLD_STICK
&& !throttleIsLow
) {
177 // Only use current throttle if not LOW - use Thr Mid otherwise
178 altHoldThrottleRCZero
= rcCommand
[THROTTLE
];
179 } else if (throttleType
== MC_ALT_HOLD_HOVER
) {
180 altHoldThrottleRCZero
= currentBatteryProfile
->nav
.mc
.hover_throttle
;
182 altHoldThrottleRCZero
= rcLookupThrottleMid();
185 // Make sure we are able to satisfy the deadband
186 altHoldThrottleRCZero
= constrain(altHoldThrottleRCZero
,
187 getThrottleIdleValue() + rcControlsConfig()->alt_hold_deadband
+ 10,
188 getMaxThrottle() - rcControlsConfig()->alt_hold_deadband
- 10);
190 // Force AH controller to initialize althold integral for pending takeoff on reset
191 // Signal for that is low throttle _and_ low actual altitude
192 if (throttleIsLow
&& fabsf(navGetCurrentActualPositionAndVelocity()->pos
.z
) <= 50.0f
) {
193 prepareForTakeoffOnReset
= true;
197 void resetMulticopterAltitudeController(void)
199 const navEstimatedPosVel_t
*posToUse
= navGetCurrentActualPositionAndVelocity();
200 float nav_speed_up
= 0.0f
;
201 float nav_speed_down
= 0.0f
;
202 float nav_accel_z
= 0.0f
;
204 navPidReset(&posControl
.pids
.vel
[Z
]);
205 navPidReset(&posControl
.pids
.surface
);
207 posControl
.rcAdjustment
[THROTTLE
] = currentBatteryProfile
->nav
.mc
.hover_throttle
;
209 posControl
.desiredState
.vel
.z
= posToUse
->vel
.z
; // Gradually transition from current climb
211 pt1FilterReset(&altholdThrottleFilterState
, 0.0f
);
212 pt1FilterReset(&posControl
.pids
.vel
[Z
].error_filter_state
, 0.0f
);
213 pt1FilterReset(&posControl
.pids
.vel
[Z
].dterm_filter_state
, 0.0f
);
215 if (FLIGHT_MODE(FAILSAFE_MODE
) || FLIGHT_MODE(NAV_RTH_MODE
) || FLIGHT_MODE(NAV_WP_MODE
) || navigationIsExecutingAnEmergencyLanding()) {
216 nav_speed_up
= navConfig()->mc
.max_auto_climb_rate
;
217 nav_accel_z
= navConfig()->mc
.max_auto_climb_rate
;
218 nav_speed_down
= navConfig()->mc
.max_auto_climb_rate
;
220 nav_speed_up
= navConfig()->mc
.max_manual_climb_rate
;
221 nav_accel_z
= navConfig()->mc
.max_manual_climb_rate
;
222 nav_speed_down
= navConfig()->mc
.max_manual_climb_rate
;
226 &alt_hold_sqrt_controller
,
227 posControl
.pids
.pos
[Z
].param
.kP
,
228 -fabsf(nav_speed_down
),
234 static void applyMulticopterAltitudeController(timeUs_t currentTimeUs
)
236 static timeUs_t previousTimePositionUpdate
= 0; // Occurs @ altitude sensor update rate (max MAX_ALTITUDE_UPDATE_RATE_HZ)
238 // If we have an update on vertical position data - update velocity and accel targets
239 if (posControl
.flags
.verticalPositionDataNew
) {
240 const timeDeltaLarge_t deltaMicrosPositionUpdate
= currentTimeUs
- previousTimePositionUpdate
;
241 previousTimePositionUpdate
= currentTimeUs
;
243 // Check if last correction was not too long ago
244 if (deltaMicrosPositionUpdate
< MAX_POSITION_UPDATE_INTERVAL_US
) {
245 // If we are preparing for takeoff - start with lowset possible climb rate, adjust alt target and make sure throttle doesn't jump
246 if (prepareForTakeoffOnReset
) {
247 const navEstimatedPosVel_t
*posToUse
= navGetCurrentActualPositionAndVelocity();
249 posControl
.desiredState
.vel
.z
= -navConfig()->mc
.max_manual_climb_rate
;
250 posControl
.desiredState
.pos
.z
= posToUse
->pos
.z
- (navConfig()->mc
.max_manual_climb_rate
/ posControl
.pids
.pos
[Z
].param
.kP
);
251 posControl
.pids
.vel
[Z
].integrator
= -500.0f
;
252 pt1FilterReset(&altholdThrottleFilterState
, -500.0f
);
253 prepareForTakeoffOnReset
= false;
256 // Execute actual altitude controllers
257 updateAltitudeVelocityController_MC(deltaMicrosPositionUpdate
);
258 updateAltitudeThrottleController_MC(deltaMicrosPositionUpdate
);
261 // Position update has not occurred in time (first start or glitch), reset altitude controller
262 resetMulticopterAltitudeController();
265 // Indicate that information is no longer usable
266 posControl
.flags
.verticalPositionDataConsumed
= true;
269 // Update throttle controller
270 rcCommand
[THROTTLE
] = posControl
.rcAdjustment
[THROTTLE
];
272 // Save processed throttle for future use
273 rcCommandAdjustedThrottle
= rcCommand
[THROTTLE
];
276 /*-----------------------------------------------------------
277 * Adjusts desired heading from pilot's input
278 *-----------------------------------------------------------*/
279 bool adjustMulticopterHeadingFromRCInput(void)
281 if (ABS(rcCommand
[YAW
]) > rcControlsConfig()->pos_hold_deadband
) {
282 // Heading during Cruise Hold mode set by Nav function so no adjustment required here
283 if (!FLIGHT_MODE(NAV_COURSE_HOLD_MODE
)) {
284 posControl
.desiredState
.yaw
= posControl
.actualState
.yaw
;
293 /*-----------------------------------------------------------
294 * XY-position controller for multicopter aircraft
295 *-----------------------------------------------------------*/
296 static float lastAccelTargetX
= 0.0f
, lastAccelTargetY
= 0.0f
;
298 void resetMulticopterBrakingMode(void)
300 DISABLE_STATE(NAV_CRUISE_BRAKING
);
301 DISABLE_STATE(NAV_CRUISE_BRAKING_BOOST
);
302 DISABLE_STATE(NAV_CRUISE_BRAKING_LOCKED
);
305 static void processMulticopterBrakingMode(const bool isAdjusting
)
307 #ifdef USE_MR_BRAKING_MODE
308 static uint32_t brakingModeDisengageAt
= 0;
309 static uint32_t brakingBoostModeDisengageAt
= 0;
311 if (!(NAV_Status
.state
== MW_NAV_STATE_NONE
|| NAV_Status
.state
== MW_NAV_STATE_HOLD_INFINIT
)) {
312 resetMulticopterBrakingMode();
316 const bool brakingEntryAllowed
=
317 IS_RC_MODE_ACTIVE(BOXBRAKING
) &&
318 !STATE(NAV_CRUISE_BRAKING_LOCKED
) &&
319 posControl
.actualState
.velXY
> navConfig()->mc
.braking_speed_threshold
&&
321 navConfig()->general
.flags
.user_control_mode
== NAV_GPS_CRUISE
&&
322 navConfig()->mc
.braking_speed_threshold
> 0;
326 * Case one, when we order to brake (sticks to the center) and we are moving above threshold
327 * Speed is above 1m/s and sticks are centered
328 * Extra condition: BRAKING flight mode has to be enabled
330 if (brakingEntryAllowed
) {
332 * Set currnt position and target position
333 * Enabling NAV_CRUISE_BRAKING locks other routines from setting position!
335 setDesiredPosition(&navGetCurrentActualPositionAndVelocity()->pos
, 0, NAV_POS_UPDATE_XY
);
337 ENABLE_STATE(NAV_CRUISE_BRAKING_LOCKED
);
338 ENABLE_STATE(NAV_CRUISE_BRAKING
);
340 //Set forced BRAKING disengage moment
341 brakingModeDisengageAt
= millis() + navConfig()->mc
.braking_timeout
;
343 //If speed above threshold, start boost mode as well
344 if (posControl
.actualState
.velXY
> navConfig()->mc
.braking_boost_speed_threshold
) {
345 ENABLE_STATE(NAV_CRUISE_BRAKING_BOOST
);
347 brakingBoostModeDisengageAt
= millis() + navConfig()->mc
.braking_boost_timeout
;
352 // We can enter braking only after user started to move the sticks
353 if (STATE(NAV_CRUISE_BRAKING_LOCKED
) && isAdjusting
) {
354 DISABLE_STATE(NAV_CRUISE_BRAKING_LOCKED
);
358 * Case when speed dropped, disengage BREAKING_BOOST
361 STATE(NAV_CRUISE_BRAKING_BOOST
) && (
362 posControl
.actualState
.velXY
<= navConfig()->mc
.braking_boost_disengage_speed
||
363 brakingBoostModeDisengageAt
< millis()
365 DISABLE_STATE(NAV_CRUISE_BRAKING_BOOST
);
369 * Case when we were braking but copter finally stopped or we started to move the sticks
371 if (STATE(NAV_CRUISE_BRAKING
) && (
372 posControl
.actualState
.velXY
<= navConfig()->mc
.braking_disengage_speed
|| //We stopped
373 isAdjusting
|| //Moved the sticks
374 brakingModeDisengageAt
< millis() //Braking is done to timed disengage
376 DISABLE_STATE(NAV_CRUISE_BRAKING
);
377 DISABLE_STATE(NAV_CRUISE_BRAKING_BOOST
);
380 * When braking is done, store current position as desired one
381 * We do not want to go back to the place where braking has started
383 setDesiredPosition(&navGetCurrentActualPositionAndVelocity()->pos
, 0, NAV_POS_UPDATE_XY
);
390 void resetMulticopterPositionController(void)
392 for (int axis
= 0; axis
< 2; axis
++) {
393 navPidReset(&posControl
.pids
.vel
[axis
]);
394 posControl
.rcAdjustment
[axis
] = 0;
395 lastAccelTargetX
= 0.0f
;
396 lastAccelTargetY
= 0.0f
;
400 static bool adjustMulticopterCruiseSpeed(int16_t rcPitchAdjustment
)
402 static timeMs_t lastUpdateTimeMs
;
403 const timeMs_t currentTimeMs
= millis();
404 const timeMs_t updateDeltaTimeMs
= currentTimeMs
- lastUpdateTimeMs
;
405 lastUpdateTimeMs
= currentTimeMs
;
407 const float rcVelX
= rcPitchAdjustment
* navConfig()->general
.max_manual_speed
/ (float)(500 - rcControlsConfig()->pos_hold_deadband
);
409 if (rcVelX
> posControl
.cruise
.multicopterSpeed
) {
410 posControl
.cruise
.multicopterSpeed
= rcVelX
;
411 } else if (rcVelX
< 0 && updateDeltaTimeMs
< 100) {
412 posControl
.cruise
.multicopterSpeed
+= MS2S(updateDeltaTimeMs
) * rcVelX
/ 2.0f
;
416 posControl
.cruise
.multicopterSpeed
= constrainf(posControl
.cruise
.multicopterSpeed
, 10.0f
, navConfig()->general
.max_manual_speed
);
421 static void setMulticopterStopPosition(void)
423 fpVector3_t stopPosition
;
424 calculateMulticopterInitialHoldPosition(&stopPosition
);
425 setDesiredPosition(&stopPosition
, 0, NAV_POS_UPDATE_XY
);
428 bool adjustMulticopterPositionFromRCInput(int16_t rcPitchAdjustment
, int16_t rcRollAdjustment
)
430 if (navGetMappedFlightModes(posControl
.navState
) & NAV_COURSE_HOLD_MODE
) {
431 if (rcPitchAdjustment
) {
432 return adjustMulticopterCruiseSpeed(rcPitchAdjustment
);
438 // Process braking mode
439 processMulticopterBrakingMode(rcPitchAdjustment
|| rcRollAdjustment
);
441 // Actually change position
442 if (rcPitchAdjustment
|| rcRollAdjustment
) {
443 // If mode is GPS_CRUISE, move target position, otherwise POS controller will passthru the RC input to ANGLE PID
444 if (navConfig()->general
.flags
.user_control_mode
== NAV_GPS_CRUISE
) {
445 const float rcVelX
= rcPitchAdjustment
* navConfig()->general
.max_manual_speed
/ (float)(500 - rcControlsConfig()->pos_hold_deadband
);
446 const float rcVelY
= rcRollAdjustment
* navConfig()->general
.max_manual_speed
/ (float)(500 - rcControlsConfig()->pos_hold_deadband
);
448 // Rotate these velocities from body frame to to earth frame
449 const float neuVelX
= rcVelX
* posControl
.actualState
.cosYaw
- rcVelY
* posControl
.actualState
.sinYaw
;
450 const float neuVelY
= rcVelX
* posControl
.actualState
.sinYaw
+ rcVelY
* posControl
.actualState
.cosYaw
;
452 // Calculate new position target, so Pos-to-Vel P-controller would yield desired velocity
453 posControl
.desiredState
.pos
.x
= navGetCurrentActualPositionAndVelocity()->pos
.x
+ (neuVelX
/ posControl
.pids
.pos
[X
].param
.kP
);
454 posControl
.desiredState
.pos
.y
= navGetCurrentActualPositionAndVelocity()->pos
.y
+ (neuVelY
/ posControl
.pids
.pos
[Y
].param
.kP
);
459 else if (posControl
.flags
.isAdjustingPosition
) {
460 // Adjusting finished - reset desired position to stay exactly where pilot released the stick
461 setMulticopterStopPosition();
467 static float getVelocityHeadingAttenuationFactor(void)
469 // In WP mode scale velocity if heading is different from bearing
470 if (navConfig()->mc
.slowDownForTurning
&& (navGetCurrentStateFlags() & NAV_AUTO_WP
)) {
471 const int32_t headingError
= constrain(wrap_18000(posControl
.desiredState
.yaw
- posControl
.actualState
.yaw
), -9000, 9000);
472 const float velScaling
= cos_approx(CENTIDEGREES_TO_RADIANS(headingError
));
474 return constrainf(velScaling
* velScaling
, 0.05f
, 1.0f
);
480 static float getVelocityExpoAttenuationFactor(float velTotal
, float velMax
)
482 // Calculate factor of how velocity with applied expo is different from unchanged velocity
483 const float velScale
= constrainf(velTotal
/ velMax
, 0.01f
, 1.0f
);
485 // navConfig()->max_speed * ((velScale * velScale * velScale) * posControl.posResponseExpo + velScale * (1 - posControl.posResponseExpo)) / velTotal;
486 // ((velScale * velScale * velScale) * posControl.posResponseExpo + velScale * (1 - posControl.posResponseExpo)) / velScale
487 // ((velScale * velScale) * posControl.posResponseExpo + (1 - posControl.posResponseExpo));
488 return 1.0f
- posControl
.posResponseExpo
* (1.0f
- (velScale
* velScale
)); // x^3 expo factor
491 static void updatePositionVelocityController_MC(const float maxSpeed
)
493 if (FLIGHT_MODE(NAV_COURSE_HOLD_MODE
)) {
494 // Position held at cruise speeds below 0.5 m/s, otherwise desired neu velocities set directly from cruise speed
495 if (posControl
.cruise
.multicopterSpeed
>= 50) {
496 // Rotate multicopter x velocity from body frame to earth frame
497 posControl
.desiredState
.vel
.x
= posControl
.cruise
.multicopterSpeed
* cos_approx(CENTIDEGREES_TO_RADIANS(posControl
.cruise
.course
));
498 posControl
.desiredState
.vel
.y
= posControl
.cruise
.multicopterSpeed
* sin_approx(CENTIDEGREES_TO_RADIANS(posControl
.cruise
.course
));
501 } else if (posControl
.flags
.isAdjustingPosition
) {
502 setMulticopterStopPosition();
506 const float posErrorX
= posControl
.desiredState
.pos
.x
- navGetCurrentActualPositionAndVelocity()->pos
.x
;
507 const float posErrorY
= posControl
.desiredState
.pos
.y
- navGetCurrentActualPositionAndVelocity()->pos
.y
;
509 // Calculate target velocity
510 float neuVelX
= posErrorX
* posControl
.pids
.pos
[X
].param
.kP
;
511 float neuVelY
= posErrorY
* posControl
.pids
.pos
[Y
].param
.kP
;
513 // Scale velocity to respect max_speed
514 float neuVelTotal
= calc_length_pythagorean_2D(neuVelX
, neuVelY
);
517 * We override computed speed with max speed in following cases:
518 * 1 - computed velocity is > maxSpeed
519 * 2 - in WP mission or RTH Trackback when: slowDownForTurning is OFF, not a hold waypoint and computed speed is < maxSpeed
522 ((navGetCurrentStateFlags() & NAV_AUTO_WP
|| posControl
.flags
.rthTrackbackActive
) &&
523 !isNavHoldPositionActive() &&
524 neuVelTotal
< maxSpeed
&&
525 !navConfig()->mc
.slowDownForTurning
526 ) || neuVelTotal
> maxSpeed
528 neuVelX
= maxSpeed
* (neuVelX
/ neuVelTotal
);
529 neuVelY
= maxSpeed
* (neuVelY
/ neuVelTotal
);
530 neuVelTotal
= maxSpeed
;
533 posControl
.pids
.pos
[X
].output_constrained
= neuVelX
;
534 posControl
.pids
.pos
[Y
].output_constrained
= neuVelY
;
536 // Apply expo & attenuation if heading in wrong direction - turn first, accelerate later (effective only in WP mode)
537 const float velHeadFactor
= getVelocityHeadingAttenuationFactor();
538 const float velExpoFactor
= getVelocityExpoAttenuationFactor(neuVelTotal
, maxSpeed
);
539 posControl
.desiredState
.vel
.x
= neuVelX
* velHeadFactor
* velExpoFactor
;
540 posControl
.desiredState
.vel
.y
= neuVelY
* velHeadFactor
* velExpoFactor
;
543 static float computeNormalizedVelocity(const float value
, const float maxValue
)
545 return constrainf(scaleRangef(fabsf(value
), 0, maxValue
, 0.0f
, 1.0f
), 0.0f
, 1.0f
);
548 static float computeVelocityScale(
550 const float maxValue
,
551 const float attenuationFactor
,
552 const float attenuationStart
,
553 const float attenuationEnd
556 const float normalized
= computeNormalizedVelocity(value
, maxValue
);
558 float scale
= scaleRangef(normalized
, attenuationStart
, attenuationEnd
, 0, attenuationFactor
);
559 return constrainf(scale
, 0, attenuationFactor
);
562 static void updatePositionAccelController_MC(timeDelta_t deltaMicros
, float maxAccelLimit
, const float maxSpeed
)
564 const float measurementX
= navGetCurrentActualPositionAndVelocity()->vel
.x
;
565 const float measurementY
= navGetCurrentActualPositionAndVelocity()->vel
.y
;
567 const float setpointX
= posControl
.desiredState
.vel
.x
;
568 const float setpointY
= posControl
.desiredState
.vel
.y
;
569 const float setpointXY
= calc_length_pythagorean_2D(setpointX
, setpointY
);
571 // Calculate velocity error
572 const float velErrorX
= setpointX
- measurementX
;
573 const float velErrorY
= setpointY
- measurementY
;
575 // Calculate XY-acceleration limit according to velocity error limit
576 float accelLimitX
, accelLimitY
;
577 const float velErrorMagnitude
= calc_length_pythagorean_2D(velErrorX
, velErrorY
);
579 if (velErrorMagnitude
> 0.1f
) {
580 accelLimitX
= maxAccelLimit
/ velErrorMagnitude
* fabsf(velErrorX
);
581 accelLimitY
= maxAccelLimit
/ velErrorMagnitude
* fabsf(velErrorY
);
583 accelLimitX
= maxAccelLimit
/ 1.414213f
;
584 accelLimitY
= accelLimitX
;
587 // Apply additional jerk limiting of 1700 cm/s^3 (~100 deg/s), almost any copter should be able to achieve this rate
588 // This will assure that we wont't saturate out LEVEL and RATE PID controller
590 float maxAccelChange
= US2S(deltaMicros
) * MC_POS_CONTROL_JERK_LIMIT_CMSSS
;
591 //When braking, raise jerk limit even if we are not boosting acceleration
592 #ifdef USE_MR_BRAKING_MODE
593 if (STATE(NAV_CRUISE_BRAKING
)) {
594 maxAccelChange
= maxAccelChange
* 2;
598 const float accelLimitXMin
= constrainf(lastAccelTargetX
- maxAccelChange
, -accelLimitX
, +accelLimitX
);
599 const float accelLimitXMax
= constrainf(lastAccelTargetX
+ maxAccelChange
, -accelLimitX
, +accelLimitX
);
600 const float accelLimitYMin
= constrainf(lastAccelTargetY
- maxAccelChange
, -accelLimitY
, +accelLimitY
);
601 const float accelLimitYMax
= constrainf(lastAccelTargetY
+ maxAccelChange
, -accelLimitY
, +accelLimitY
);
603 // TODO: Verify if we need jerk limiting after all
606 * This PID controller has dynamic dTerm scale. It's less active when controller
607 * is tracking setpoint at high speed. Full dTerm is required only for position hold,
608 * acceleration and deceleration
609 * Scale down dTerm with 2D speed
611 const float setpointScale
= computeVelocityScale(
614 multicopterPosXyCoefficients
.dTermAttenuation
,
615 multicopterPosXyCoefficients
.dTermAttenuationStart
,
616 multicopterPosXyCoefficients
.dTermAttenuationEnd
618 const float measurementScale
= computeVelocityScale(
619 posControl
.actualState
.velXY
,
621 multicopterPosXyCoefficients
.dTermAttenuation
,
622 multicopterPosXyCoefficients
.dTermAttenuationStart
,
623 multicopterPosXyCoefficients
.dTermAttenuationEnd
626 //Choose smaller attenuation factor and convert from attenuation to scale
627 const float dtermScale
= 1.0f
- MIN(setpointScale
, measurementScale
);
629 // Apply PID with output limiting and I-term anti-windup
630 // Pre-calculated accelLimit and the logic of navPidApply2 function guarantee that our newAccel won't exceed maxAccelLimit
631 // Thus we don't need to do anything else with calculated acceleration
632 float newAccelX
= navPidApply3(
633 &posControl
.pids
.vel
[X
],
640 1.0f
, // Total gain scale
641 dtermScale
// Additional dTerm scale
643 float newAccelY
= navPidApply3(
644 &posControl
.pids
.vel
[Y
],
651 1.0f
, // Total gain scale
652 dtermScale
// Additional dTerm scale
655 int32_t maxBankAngle
= DEGREES_TO_DECIDEGREES(navConfig()->mc
.max_bank_angle
);
657 #ifdef USE_MR_BRAKING_MODE
658 //Boost required accelerations
659 if (STATE(NAV_CRUISE_BRAKING_BOOST
) && multicopterPosXyCoefficients
.breakingBoostFactor
> 0.0f
) {
661 //Scale boost factor according to speed
662 const float boostFactor
= constrainf(
664 posControl
.actualState
.velXY
,
665 navConfig()->mc
.braking_boost_speed_threshold
,
666 navConfig()->general
.max_manual_speed
,
668 multicopterPosXyCoefficients
.breakingBoostFactor
671 multicopterPosXyCoefficients
.breakingBoostFactor
674 //Boost required acceleration for harder braking
675 newAccelX
= newAccelX
* (1.0f
+ boostFactor
);
676 newAccelY
= newAccelY
* (1.0f
+ boostFactor
);
678 maxBankAngle
= DEGREES_TO_DECIDEGREES(navConfig()->mc
.braking_bank_angle
);
682 // Save last acceleration target
683 lastAccelTargetX
= newAccelX
;
684 lastAccelTargetY
= newAccelY
;
686 // Rotate acceleration target into forward-right frame (aircraft)
687 const float accelForward
= newAccelX
* posControl
.actualState
.cosYaw
+ newAccelY
* posControl
.actualState
.sinYaw
;
688 const float accelRight
= -newAccelX
* posControl
.actualState
.sinYaw
+ newAccelY
* posControl
.actualState
.cosYaw
;
690 // Calculate banking angles
691 const float desiredPitch
= atan2_approx(accelForward
, GRAVITY_CMSS
);
692 const float desiredRoll
= atan2_approx(accelRight
* cos_approx(desiredPitch
), GRAVITY_CMSS
);
694 posControl
.rcAdjustment
[ROLL
] = constrain(RADIANS_TO_DECIDEGREES(desiredRoll
), -maxBankAngle
, maxBankAngle
);
695 posControl
.rcAdjustment
[PITCH
] = constrain(RADIANS_TO_DECIDEGREES(desiredPitch
), -maxBankAngle
, maxBankAngle
);
698 static void applyMulticopterPositionController(timeUs_t currentTimeUs
)
700 // Apply controller only if position source is valid. In absence of valid pos sensor (GPS loss), we'd stick in forced ANGLE mode
701 // and pilots input would be passed thru to PID controller
702 if (posControl
.flags
.estPosStatus
< EST_USABLE
) {
703 /* No position data, disable automatic adjustment, rcCommand passthrough */
704 posControl
.rcAdjustment
[PITCH
] = 0;
705 posControl
.rcAdjustment
[ROLL
] = 0;
710 // Passthrough rcCommand if adjusting position in GPS_ATTI mode except when Course Hold active
711 bool bypassPositionController
= !FLIGHT_MODE(NAV_COURSE_HOLD_MODE
) &&
712 navConfig()->general
.flags
.user_control_mode
== NAV_GPS_ATTI
&&
713 posControl
.flags
.isAdjustingPosition
;
715 if (posControl
.flags
.horizontalPositionDataNew
) {
716 // Indicate that information is no longer usable
717 posControl
.flags
.horizontalPositionDataConsumed
= true;
719 static timeUs_t previousTimePositionUpdate
= 0; // Occurs @ GPS update rate
720 const timeDeltaLarge_t deltaMicrosPositionUpdate
= currentTimeUs
- previousTimePositionUpdate
;
721 previousTimePositionUpdate
= currentTimeUs
;
723 if (bypassPositionController
) {
727 // If we have new position data - update velocity and acceleration controllers
728 if (deltaMicrosPositionUpdate
< MAX_POSITION_UPDATE_INTERVAL_US
) {
729 // Get max speed for current NAV mode
730 float maxSpeed
= getActiveSpeed();
731 updatePositionVelocityController_MC(maxSpeed
);
732 updatePositionAccelController_MC(deltaMicrosPositionUpdate
, NAV_ACCELERATION_XY_MAX
, maxSpeed
);
734 navDesiredVelocity
[X
] = constrain(lrintf(posControl
.desiredState
.vel
.x
), -32678, 32767);
735 navDesiredVelocity
[Y
] = constrain(lrintf(posControl
.desiredState
.vel
.y
), -32678, 32767);
738 // Position update has not occurred in time (first start or glitch), reset position controller
739 resetMulticopterPositionController();
741 } else if (bypassPositionController
) {
745 rcCommand
[PITCH
] = pidAngleToRcCommand(posControl
.rcAdjustment
[PITCH
], pidProfile()->max_angle_inclination
[FD_PITCH
]);
746 rcCommand
[ROLL
] = pidAngleToRcCommand(posControl
.rcAdjustment
[ROLL
], pidProfile()->max_angle_inclination
[FD_ROLL
]);
749 bool isMulticopterFlying(void)
751 bool throttleCondition
= rcCommand
[THROTTLE
] > currentBatteryProfile
->nav
.mc
.hover_throttle
;
752 bool gyroCondition
= averageAbsGyroRates() > 7.0f
;
754 return throttleCondition
&& gyroCondition
;
757 /*-----------------------------------------------------------
758 * Multicopter land detector
759 *-----------------------------------------------------------*/
760 #if defined(USE_BARO)
761 static float baroAltRate
;
763 void updateBaroAltitudeRate(float newBaroAltRate
)
765 baroAltRate
= newBaroAltRate
;
768 static bool isLandingGbumpDetected(timeMs_t currentTimeMs
)
770 /* Detection based on G bump at touchdown, falling Baro altitude and throttle below hover.
771 * G bump trigger: > 2g then falling back below 1g in < 0.1s.
772 * Baro trigger: rate must be -ve at initial trigger g and < -2 m/s when g falls back below 1g
773 * Throttle trigger: must be below hover throttle with lower threshold for manual throttle control */
775 static timeMs_t gSpikeDetectTimeMs
= 0;
777 if (!gSpikeDetectTimeMs
&& acc
.accADCf
[Z
] > 2.0f
&& baroAltRate
< 0.0f
) {
778 gSpikeDetectTimeMs
= currentTimeMs
;
779 } else if (gSpikeDetectTimeMs
) {
780 if (currentTimeMs
< gSpikeDetectTimeMs
+ 100) {
781 if (acc
.accADCf
[Z
] < 1.0f
&& baroAltRate
< -200.0f
) {
782 const uint16_t idleThrottle
= getThrottleIdleValue();
783 const uint16_t hoverThrottleRange
= currentBatteryProfile
->nav
.mc
.hover_throttle
- idleThrottle
;
784 return rcCommand
[THROTTLE
] < idleThrottle
+ ((navigationInAutomaticThrottleMode() ? 0.8 : 0.5) * hoverThrottleRange
);
786 } else if (acc
.accADCf
[Z
] <= 1.0f
) {
787 gSpikeDetectTimeMs
= 0;
794 bool isMulticopterCrashedInverted(timeMs_t currentTimeMs
)
796 /* Disarms MR if inverted on the ground. Checks vertical velocity is low based on Baro rate below 2 m/s */
798 static timeMs_t startTime
= 0;
800 if ((ABS(attitude
.values
.roll
) > 1000 || ABS(attitude
.values
.pitch
) > 700) && fabsf(baroAltRate
) < 200.0f
) {
801 if (startTime
== 0) {
802 startTime
= currentTimeMs
;
805 /* Minimum 3s disarm delay + extra user set delay time (min overall delay of 4s) */
806 uint16_t disarmTimeDelay
= 3000 + S2MS(navConfig()->mc
.inverted_crash_detection
);
807 return currentTimeMs
- startTime
> disarmTimeDelay
;
815 bool isMulticopterLandingDetected(void)
817 DEBUG_SET(DEBUG_LANDING
, 4, 0);
818 DEBUG_SET(DEBUG_LANDING
, 3, averageAbsGyroRates() * 100);
820 const timeMs_t currentTimeMs
= millis();
822 #if defined(USE_BARO)
823 if (sensors(SENSOR_BARO
)) {
824 /* Inverted crash landing detection - immediate disarm */
825 if (navConfig()->mc
.inverted_crash_detection
&& !FLIGHT_MODE(TURTLE_MODE
) && isMulticopterCrashedInverted(currentTimeMs
)) {
826 ENABLE_ARMING_FLAG(ARMING_DISABLED_LANDING_DETECTED
);
827 disarm(DISARM_LANDING
);
830 /* G bump landing detection *
831 * Only used when xy velocity is low or failsafe is active */
832 bool gBumpDetectionUsable
= navConfig()->general
.flags
.landing_bump_detection
&&
833 ((posControl
.flags
.estPosStatus
>= EST_USABLE
&& posControl
.actualState
.velXY
< MC_LAND_CHECK_VEL_XY_MOVING
) ||
834 FLIGHT_MODE(FAILSAFE_MODE
));
836 if (gBumpDetectionUsable
&& isLandingGbumpDetected(currentTimeMs
)) {
837 return true; // Landing flagged immediately if landing bump detected
842 bool throttleIsBelowMidHover
= rcCommand
[THROTTLE
] < (0.5 * (currentBatteryProfile
->nav
.mc
.hover_throttle
+ getThrottleIdleValue()));
844 /* Basic condition to start looking for landing
845 * Detection active during Failsafe only if throttle below mid hover throttle
846 * and WP mission not active (except landing states).
847 * Also active in non autonomous flight modes but only when thottle low */
848 bool startCondition
= (navGetCurrentStateFlags() & (NAV_CTL_LAND
| NAV_CTL_EMERG
))
849 || (FLIGHT_MODE(FAILSAFE_MODE
) && !FLIGHT_MODE(NAV_WP_MODE
) && throttleIsBelowMidHover
)
850 || (!navigationIsFlyingAutonomousMode() && throttleStickIsLow());
852 static timeMs_t landingDetectorStartedAt
;
854 if (!startCondition
|| posControl
.flags
.resetLandingDetector
) {
855 landingDetectorStartedAt
= 0;
856 return posControl
.flags
.resetLandingDetector
= false;
859 const float sensitivity
= navConfig()->general
.land_detect_sensitivity
/ 5.0f
;
861 // check vertical and horizontal velocities are low (cm/s)
862 bool velCondition
= fabsf(navGetCurrentActualPositionAndVelocity()->vel
.z
) < (MC_LAND_CHECK_VEL_Z_MOVING
* sensitivity
) &&
863 posControl
.actualState
.velXY
< (MC_LAND_CHECK_VEL_XY_MOVING
* sensitivity
);
864 // check gyro rates are low (degs/s)
865 bool gyroCondition
= averageAbsGyroRates() < (4.0f
* sensitivity
);
866 DEBUG_SET(DEBUG_LANDING
, 2, velCondition
);
867 DEBUG_SET(DEBUG_LANDING
, 3, gyroCondition
);
869 bool possibleLandingDetected
= false;
871 if (navGetCurrentStateFlags() & NAV_CTL_LAND
) {
872 // We have likely landed if throttle is 40 units below average descend throttle
873 // We use rcCommandAdjustedThrottle to keep track of NAV corrected throttle (isLandingDetected is executed
874 // from processRx() and rcCommand at that moment holds rc input, not adjusted values from NAV core)
875 DEBUG_SET(DEBUG_LANDING
, 4, 1);
877 static int32_t landingThrSum
;
878 static int32_t landingThrSamples
;
879 bool isAtMinimalThrust
= false;
881 if (!landingDetectorStartedAt
) {
882 landingThrSum
= landingThrSamples
= 0;
883 landingDetectorStartedAt
= currentTimeMs
;
885 if (!landingThrSamples
) {
886 if (currentTimeMs
- landingDetectorStartedAt
< S2MS(MC_LAND_THR_STABILISE_DELAY
)) { // Wait for 1 second so throttle has stabilized.
889 landingDetectorStartedAt
= currentTimeMs
;
892 landingThrSamples
+= 1;
893 landingThrSum
+= rcCommandAdjustedThrottle
;
894 isAtMinimalThrust
= rcCommandAdjustedThrottle
< (landingThrSum
/ landingThrSamples
- MC_LAND_DESCEND_THROTTLE
);
896 possibleLandingDetected
= isAtMinimalThrust
&& velCondition
;
898 DEBUG_SET(DEBUG_LANDING
, 6, rcCommandAdjustedThrottle
);
899 DEBUG_SET(DEBUG_LANDING
, 7, landingThrSum
/ landingThrSamples
- MC_LAND_DESCEND_THROTTLE
);
900 } else { // non autonomous and emergency landing
901 DEBUG_SET(DEBUG_LANDING
, 4, 2);
902 if (landingDetectorStartedAt
) {
903 possibleLandingDetected
= velCondition
&& gyroCondition
;
905 landingDetectorStartedAt
= currentTimeMs
;
910 // If we have surface sensor (for example sonar) - use it to detect touchdown
911 if ((posControl
.flags
.estAglStatus
== EST_TRUSTED
) && (posControl
.actualState
.agl
.pos
.z
>= 0)) {
912 // TODO: Come up with a clever way to let sonar increase detection performance, not just add extra safety.
913 // TODO: Out of range sonar may give reading that looks like we landed, find a way to check if sonar is healthy.
914 // surfaceMin is our ground reference. If we are less than 5cm above the ground - we are likely landed
915 possibleLandingDetected
= possibleLandingDetected
&& (posControl
.actualState
.agl
.pos
.z
<= (posControl
.actualState
.surfaceMin
+ MC_LAND_SAFE_SURFACE
));
917 DEBUG_SET(DEBUG_LANDING
, 5, possibleLandingDetected
);
919 if (possibleLandingDetected
) {
920 /* Conditions need to be held for fixed safety time + optional extra delay.
921 * Fixed time increased if Z velocity invalid to provide extra safety margin against false triggers */
922 const uint16_t safetyTime
= posControl
.flags
.estAltStatus
== EST_NONE
? 5000 : 1000;
923 timeMs_t safetyTimeDelay
= safetyTime
+ navConfig()->general
.auto_disarm_delay
;
924 return currentTimeMs
- landingDetectorStartedAt
> safetyTimeDelay
;
926 landingDetectorStartedAt
= currentTimeMs
;
931 /*-----------------------------------------------------------
932 * Multicopter emergency landing
933 *-----------------------------------------------------------*/
934 static void applyMulticopterEmergencyLandingController(timeUs_t currentTimeUs
)
936 static timeUs_t previousTimePositionUpdate
= 0;
938 /* Attempt to stabilise */
941 rcCommand
[PITCH
] = 0;
943 /* Altitude sensors gone haywire, attempt to land regardless */
944 if (posControl
.flags
.estAltStatus
< EST_USABLE
) {
945 if (failsafeConfig()->failsafe_procedure
== FAILSAFE_PROCEDURE_DROP_IT
) {
946 rcCommand
[THROTTLE
] = getThrottleIdleValue();
949 rcCommand
[THROTTLE
] = setDesiredThrottle(currentBatteryProfile
->failsafe_throttle
, true);
953 // Normal sensor data available, use controlled landing descent
954 if (posControl
.flags
.verticalPositionDataNew
) {
955 const timeDeltaLarge_t deltaMicrosPositionUpdate
= currentTimeUs
- previousTimePositionUpdate
;
956 previousTimePositionUpdate
= currentTimeUs
;
958 // Check if last correction was not too long ago
959 if (deltaMicrosPositionUpdate
< MAX_POSITION_UPDATE_INTERVAL_US
) {
960 // target min descent rate at distance 2 x emerg descent rate above takeoff altitude
961 updateClimbRateToAltitudeController(0, 2.0f
* navConfig()->general
.emerg_descent_rate
, ROC_TO_ALT_TARGET
);
962 updateAltitudeVelocityController_MC(deltaMicrosPositionUpdate
);
963 updateAltitudeThrottleController_MC(deltaMicrosPositionUpdate
);
966 // due to some glitch position update has not occurred in time, reset altitude controller
967 resetMulticopterAltitudeController();
970 // Indicate that information is no longer usable
971 posControl
.flags
.verticalPositionDataConsumed
= true;
975 rcCommand
[THROTTLE
] = posControl
.rcAdjustment
[THROTTLE
];
977 // Hold position if possible
978 if ((posControl
.flags
.estPosStatus
>= EST_USABLE
)) {
979 applyMulticopterPositionController(currentTimeUs
);
983 /*-----------------------------------------------------------
984 * Calculate loiter target based on current position and velocity
985 *-----------------------------------------------------------*/
986 void calculateMulticopterInitialHoldPosition(fpVector3_t
* pos
)
988 const float stoppingDistanceX
= navGetCurrentActualPositionAndVelocity()->vel
.x
* posControl
.posDecelerationTime
;
989 const float stoppingDistanceY
= navGetCurrentActualPositionAndVelocity()->vel
.y
* posControl
.posDecelerationTime
;
991 pos
->x
= navGetCurrentActualPositionAndVelocity()->pos
.x
+ stoppingDistanceX
;
992 pos
->y
= navGetCurrentActualPositionAndVelocity()->pos
.y
+ stoppingDistanceY
;
995 void resetMulticopterHeadingController(void)
997 updateHeadingHoldTarget(CENTIDEGREES_TO_DEGREES(posControl
.actualState
.yaw
));
1000 static void applyMulticopterHeadingController(void)
1002 if (FLIGHT_MODE(NAV_COURSE_HOLD_MODE
)) { // heading set by Nav during Course Hold so disable yaw stick input
1006 updateHeadingHoldTarget(CENTIDEGREES_TO_DEGREES(posControl
.desiredState
.yaw
));
1009 void applyMulticopterNavigationController(navigationFSMStateFlags_t navStateFlags
, timeUs_t currentTimeUs
)
1011 if (navStateFlags
& NAV_CTL_EMERG
) {
1012 applyMulticopterEmergencyLandingController(currentTimeUs
);
1015 if (navStateFlags
& NAV_CTL_ALT
)
1016 applyMulticopterAltitudeController(currentTimeUs
);
1018 if (navStateFlags
& NAV_CTL_POS
)
1019 applyMulticopterPositionController(currentTimeUs
);
1021 if (navStateFlags
& NAV_CTL_YAW
)
1022 applyMulticopterHeadingController();