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 "common/axis.h"
28 #include "common/maths.h"
29 #include "common/filter.h"
31 #include "drivers/time.h"
33 #include "sensors/sensors.h"
34 #include "sensors/acceleration.h"
35 #include "sensors/boardalignment.h"
36 #include "sensors/gyro.h"
37 #include "sensors/pitotmeter.h"
39 #include "flight/pid.h"
40 #include "flight/imu.h"
41 #include "flight/mixer.h"
43 #include "fc/config.h"
44 #include "fc/controlrate_profile.h"
45 #include "fc/rc_controls.h"
46 #include "fc/rc_modes.h"
47 #include "fc/runtime_config.h"
49 #include "navigation/navigation.h"
50 #include "navigation/navigation_private.h"
52 #include "programming/logic_condition.h"
56 #include "sensors/battery.h"
58 // Base frequencies for smoothing pitch and roll
59 #define NAV_FW_BASE_PITCH_CUTOFF_FREQUENCY_HZ 2.0f
60 #define NAV_FW_BASE_ROLL_CUTOFF_FREQUENCY_HZ 10.0f
62 // If we are going slower than NAV_FW_MIN_VEL_SPEED_BOOST - boost throttle to fight against the wind
63 #define NAV_FW_THROTTLE_SPEED_BOOST_GAIN 1.5f
64 #define NAV_FW_MIN_VEL_SPEED_BOOST 700.0f // 7 m/s
66 // If this is enabled navigation won't be applied if velocity is below 3 m/s
67 //#define NAV_FW_LIMIT_MIN_FLY_VELOCITY
69 static bool isPitchAdjustmentValid
= false;
70 static bool isRollAdjustmentValid
= false;
71 static bool isYawAdjustmentValid
= false;
72 static float throttleSpeedAdjustment
= 0;
73 static bool isAutoThrottleManuallyIncreased
= false;
74 static int32_t navHeadingError
;
75 static int8_t loiterDirYaw
= 1;
76 bool needToCalculateCircularLoiter
;
78 // Calculates the cutoff frequency for smoothing out roll/pitch commands
79 // control_smoothness valid range from 0 to 9
80 // resulting cutoff_freq ranging from baseFreq downwards to ~0.11Hz
81 static float getSmoothnessCutoffFreq(float baseFreq
)
83 uint16_t smoothness
= 10 - navConfig()->fw
.control_smoothness
;
84 return 0.001f
* baseFreq
* (float)(smoothness
*smoothness
*smoothness
) + 0.1f
;
87 // Calculates the cutoff frequency for smoothing out pitchToThrottleCorrection
88 // pitch_to_throttle_smooth valid range from 0 to 9
89 // resulting cutoff_freq ranging from baseFreq downwards to ~0.01Hz
90 static float getPitchToThrottleSmoothnessCutoffFreq(float baseFreq
)
92 uint16_t smoothness
= 10 - navConfig()->fw
.pitch_to_throttle_smooth
;
93 return 0.001f
* baseFreq
* (float)(smoothness
*smoothness
*smoothness
) + 0.01f
;
96 /*-----------------------------------------------------------
98 *-----------------------------------------------------------*/
99 void setupFixedWingAltitudeController(void)
104 void resetFixedWingAltitudeController(void)
106 navPidReset(&posControl
.pids
.fw_alt
);
107 posControl
.rcAdjustment
[PITCH
] = 0;
108 isPitchAdjustmentValid
= false;
109 throttleSpeedAdjustment
= 0;
112 bool adjustFixedWingAltitudeFromRCInput(void)
114 int16_t rcAdjustment
= applyDeadbandRescaled(rcCommand
[PITCH
], rcControlsConfig()->alt_hold_deadband
, -500, 500);
117 // set velocity proportional to stick movement
118 float rcClimbRate
= -rcAdjustment
* navConfig()->general
.max_manual_climb_rate
/ (500.0f
- rcControlsConfig()->alt_hold_deadband
);
119 updateClimbRateToAltitudeController(rcClimbRate
, ROC_TO_ALT_NORMAL
);
123 // Adjusting finished - reset desired position to stay exactly where pilot released the stick
124 if (posControl
.flags
.isAdjustingAltitude
) {
125 updateClimbRateToAltitudeController(0, ROC_TO_ALT_RESET
);
131 // Position to velocity controller for Z axis
132 static void updateAltitudeVelocityAndPitchController_FW(timeDelta_t deltaMicros
)
134 static pt1Filter_t velzFilterState
;
136 // On a fixed wing we might not have a reliable climb rate source (if no BARO available), so we can't apply PID controller to
137 // velocity error. We use PID controller on altitude error and calculate desired pitch angle
140 const float demSPE
= (posControl
.desiredState
.pos
.z
* 0.01f
) * GRAVITY_MSS
;
141 const float demSKE
= 0.0f
;
143 const float estSPE
= (navGetCurrentActualPositionAndVelocity()->pos
.z
* 0.01f
) * GRAVITY_MSS
;
144 const float estSKE
= 0.0f
;
146 // speedWeight controls balance between potential and kinetic energy used for pitch controller
147 // speedWeight = 1.0 : pitch will only control airspeed and won't control altitude
148 // speedWeight = 0.5 : pitch will be used to control both airspeed and altitude
149 // speedWeight = 0.0 : pitch will only control altitude
150 const float speedWeight
= 0.0f
; // no speed sensing for now
152 const float demSEB
= demSPE
* (1.0f
- speedWeight
) - demSKE
* speedWeight
;
153 const float estSEB
= estSPE
* (1.0f
- speedWeight
) - estSKE
* speedWeight
;
155 // SEB to pitch angle gain to account for airspeed (with respect to specified reference (tuning) speed
156 const float pitchGainInv
= 1.0f
/ 1.0f
;
158 // Here we use negative values for dive for better clarity
159 const float maxClimbDeciDeg
= DEGREES_TO_DECIDEGREES(navConfig()->fw
.max_climb_angle
);
160 const float minDiveDeciDeg
= -DEGREES_TO_DECIDEGREES(navConfig()->fw
.max_dive_angle
);
162 // PID controller to translate energy balance error [J] into pitch angle [decideg]
163 float targetPitchAngle
= navPidApply3(&posControl
.pids
.fw_alt
, demSEB
, estSEB
, US2S(deltaMicros
), minDiveDeciDeg
, maxClimbDeciDeg
, 0, pitchGainInv
, 1.0f
);
165 // Apply low-pass filter to prevent rapid correction
166 targetPitchAngle
= pt1FilterApply4(&velzFilterState
, targetPitchAngle
, getSmoothnessCutoffFreq(NAV_FW_BASE_PITCH_CUTOFF_FREQUENCY_HZ
), US2S(deltaMicros
));
168 // Reconstrain pitch angle ( >0 - climb, <0 - dive)
169 targetPitchAngle
= constrainf(targetPitchAngle
, minDiveDeciDeg
, maxClimbDeciDeg
);
170 posControl
.rcAdjustment
[PITCH
] = targetPitchAngle
;
173 void applyFixedWingAltitudeAndThrottleController(timeUs_t currentTimeUs
)
175 static timeUs_t previousTimePositionUpdate
= 0; // Occurs @ altitude sensor update rate (max MAX_ALTITUDE_UPDATE_RATE_HZ)
177 if ((posControl
.flags
.estAltStatus
>= EST_USABLE
)) {
178 if (posControl
.flags
.verticalPositionDataNew
) {
179 const timeDeltaLarge_t deltaMicrosPositionUpdate
= currentTimeUs
- previousTimePositionUpdate
;
180 previousTimePositionUpdate
= currentTimeUs
;
182 // Check if last correction was not too long ago
183 if (deltaMicrosPositionUpdate
< MAX_POSITION_UPDATE_INTERVAL_US
) {
184 updateAltitudeVelocityAndPitchController_FW(deltaMicrosPositionUpdate
);
187 // Position update has not occurred in time (first iteration or glitch), reset altitude controller
188 resetFixedWingAltitudeController();
191 // Indicate that information is no longer usable
192 posControl
.flags
.verticalPositionDataConsumed
= true;
195 isPitchAdjustmentValid
= true;
198 // No valid altitude sensor data, don't adjust pitch automatically, rcCommand[PITCH] is passed through to PID controller
199 isPitchAdjustmentValid
= false;
203 /*-----------------------------------------------------------
204 * Adjusts desired heading from pilot's input
205 *-----------------------------------------------------------*/
206 bool adjustFixedWingHeadingFromRCInput(void)
208 if (ABS(rcCommand
[YAW
]) > rcControlsConfig()->pos_hold_deadband
) {
215 /*-----------------------------------------------------------
216 * XY-position controller for multicopter aircraft
217 *-----------------------------------------------------------*/
218 static fpVector3_t virtualDesiredPosition
;
219 static pt1Filter_t fwPosControllerCorrectionFilterState
;
222 * TODO Currently this function resets both FixedWing and Rover & Boat position controller
224 void resetFixedWingPositionController(void)
226 virtualDesiredPosition
.x
= 0;
227 virtualDesiredPosition
.y
= 0;
228 virtualDesiredPosition
.z
= 0;
230 navPidReset(&posControl
.pids
.fw_nav
);
231 navPidReset(&posControl
.pids
.fw_heading
);
232 posControl
.rcAdjustment
[ROLL
] = 0;
233 posControl
.rcAdjustment
[YAW
] = 0;
234 isRollAdjustmentValid
= false;
235 isYawAdjustmentValid
= false;
237 pt1FilterReset(&fwPosControllerCorrectionFilterState
, 0.0f
);
240 static int8_t loiterDirection(void) {
241 int8_t dir
= 1; //NAV_LOITER_RIGHT
243 if (pidProfile()->loiter_direction
== NAV_LOITER_LEFT
) {
247 if (pidProfile()->loiter_direction
== NAV_LOITER_YAW
) {
249 if (rcCommand
[YAW
] < -250) {
250 loiterDirYaw
= 1; //RIGHT //yaw is contrariwise
253 if (rcCommand
[YAW
] > 250) {
254 loiterDirYaw
= -1; //LEFT //see annexCode in fc_core.c
260 if (IS_RC_MODE_ACTIVE(BOXLOITERDIRCHN
)) {
267 static void calculateVirtualPositionTarget_FW(float trackingPeriod
)
269 if (FLIGHT_MODE(NAV_COURSE_HOLD_MODE
)) {
273 float posErrorX
= posControl
.desiredState
.pos
.x
- navGetCurrentActualPositionAndVelocity()->pos
.x
;
274 float posErrorY
= posControl
.desiredState
.pos
.y
- navGetCurrentActualPositionAndVelocity()->pos
.y
;
276 float distanceToActualTarget
= calc_length_pythagorean_2D(posErrorX
, posErrorY
);
278 // Limit minimum forward velocity to 1 m/s
279 float trackingDistance
= trackingPeriod
* MAX(posControl
.actualState
.velXY
, 100.0f
);
281 uint32_t navLoiterRadius
= getLoiterRadius(navConfig()->fw
.loiter_radius
);
282 fpVector3_t loiterCenterPos
= posControl
.desiredState
.pos
;
283 int8_t loiterTurnDirection
= loiterDirection();
285 // Detemine if a circular loiter is required.
286 // For waypoints only use circular loiter when angular visibility is > 30 degs, otherwise head straight toward target
287 #define TAN_15DEG 0.26795f
288 needToCalculateCircularLoiter
= isNavHoldPositionActive() &&
289 (distanceToActualTarget
<= (navLoiterRadius
/ TAN_15DEG
)) &&
290 (distanceToActualTarget
> 50.0f
);
292 /* WP turn smoothing with 2 options, 1: pass through WP, 2: cut inside turn missing WP
293 * Works for turns > 30 degs and < 160 degs.
294 * Option 1 switches to loiter path around waypoint using navLoiterRadius.
295 * Loiter centered on point inside turn at required distance from waypoint and
296 * on a bearing midway between current and next waypoint course bearings.
297 * Option 2 simply uses a normal turn once the turn initiation point is reached */
298 int32_t waypointTurnAngle
= posControl
.activeWaypoint
.nextTurnAngle
== -1 ? -1 : ABS(posControl
.activeWaypoint
.nextTurnAngle
);
299 posControl
.flags
.wpTurnSmoothingActive
= false;
300 if (waypointTurnAngle
> 3000 && waypointTurnAngle
< 16000 && isWaypointNavTrackingActive() && !needToCalculateCircularLoiter
) {
301 // turnStartFactor adjusts start of loiter based on turn angle
302 float turnStartFactor
;
303 if (navConfig()->fw
.wp_turn_smoothing
== WP_TURN_SMOOTHING_ON
) { // passes through WP
304 turnStartFactor
= waypointTurnAngle
/ 6000.0f
;
305 } else { // // cut inside turn missing WP
306 turnStartFactor
= constrainf(tan_approx(CENTIDEGREES_TO_RADIANS(waypointTurnAngle
/ 2.0f
)), 1.0f
, 2.0f
);
308 // velXY provides additional turn initiation distance based on an assumed 1 second delayed turn response time
309 if (posControl
.wpDistance
< (posControl
.actualState
.velXY
+ navLoiterRadius
* turnStartFactor
)) {
310 if (navConfig()->fw
.wp_turn_smoothing
== WP_TURN_SMOOTHING_ON
) {
311 int32_t loiterCenterBearing
= wrap_36000(((wrap_18000(posControl
.activeWaypoint
.nextTurnAngle
- 18000)) / 2) + posControl
.activeWaypoint
.yaw
+ 18000);
312 loiterCenterPos
.x
= posControl
.activeWaypoint
.pos
.x
+ navLoiterRadius
* cos_approx(CENTIDEGREES_TO_RADIANS(loiterCenterBearing
));
313 loiterCenterPos
.y
= posControl
.activeWaypoint
.pos
.y
+ navLoiterRadius
* sin_approx(CENTIDEGREES_TO_RADIANS(loiterCenterBearing
));
315 posErrorX
= loiterCenterPos
.x
- navGetCurrentActualPositionAndVelocity()->pos
.x
;
316 posErrorY
= loiterCenterPos
.y
- navGetCurrentActualPositionAndVelocity()->pos
.y
;
318 // turn direction to next waypoint
319 loiterTurnDirection
= posControl
.activeWaypoint
.nextTurnAngle
> 0 ? 1 : -1; // 1 = right
321 needToCalculateCircularLoiter
= true;
323 posControl
.flags
.wpTurnSmoothingActive
= true;
327 // We are closing in on a waypoint, calculate circular loiter if required
328 if (needToCalculateCircularLoiter
) {
329 float loiterAngle
= atan2_approx(-posErrorY
, -posErrorX
) + DEGREES_TO_RADIANS(loiterTurnDirection
* 45.0f
);
330 float loiterTargetX
= loiterCenterPos
.x
+ navLoiterRadius
* cos_approx(loiterAngle
);
331 float loiterTargetY
= loiterCenterPos
.y
+ navLoiterRadius
* sin_approx(loiterAngle
);
333 // We have temporary loiter target. Recalculate distance and position error
334 posErrorX
= loiterTargetX
- navGetCurrentActualPositionAndVelocity()->pos
.x
;
335 posErrorY
= loiterTargetY
- navGetCurrentActualPositionAndVelocity()->pos
.y
;
336 distanceToActualTarget
= calc_length_pythagorean_2D(posErrorX
, posErrorY
);
339 // Calculate virtual waypoint
340 virtualDesiredPosition
.x
= navGetCurrentActualPositionAndVelocity()->pos
.x
+ posErrorX
* (trackingDistance
/ distanceToActualTarget
);
341 virtualDesiredPosition
.y
= navGetCurrentActualPositionAndVelocity()->pos
.y
+ posErrorY
* (trackingDistance
/ distanceToActualTarget
);
343 // Shift position according to pilot's ROLL input (up to max_manual_speed velocity)
344 if (posControl
.flags
.isAdjustingPosition
) {
345 int16_t rcRollAdjustment
= applyDeadbandRescaled(rcCommand
[ROLL
], rcControlsConfig()->pos_hold_deadband
, -500, 500);
347 if (rcRollAdjustment
) {
348 float rcShiftY
= rcRollAdjustment
* navConfig()->general
.max_manual_speed
/ 500.0f
* trackingPeriod
;
350 // Rotate this target shift from body frame to to earth frame and apply to position target
351 virtualDesiredPosition
.x
+= -rcShiftY
* posControl
.actualState
.sinYaw
;
352 virtualDesiredPosition
.y
+= rcShiftY
* posControl
.actualState
.cosYaw
;
357 bool adjustFixedWingPositionFromRCInput(void)
359 int16_t rcRollAdjustment
= applyDeadbandRescaled(rcCommand
[ROLL
], rcControlsConfig()->pos_hold_deadband
, -500, 500);
360 return (rcRollAdjustment
);
363 float processHeadingYawController(timeDelta_t deltaMicros
, int32_t navHeadingError
, bool errorIsDecreasing
) {
364 static float limit
= 0.0f
;
367 limit
= pidProfile()->navFwPosHdgPidsumLimit
* 100.0f
;
370 const pidControllerFlags_e yawPidFlags
= errorIsDecreasing
? PID_SHRINK_INTEGRATOR
: 0;
372 const float yawAdjustment
= navPidApply2(
373 &posControl
.pids
.fw_heading
,
375 applyDeadband(navHeadingError
, navConfig()->fw
.yawControlDeadband
* 100),
382 DEBUG_SET(DEBUG_NAV_YAW
, 0, posControl
.pids
.fw_heading
.proportional
);
383 DEBUG_SET(DEBUG_NAV_YAW
, 1, posControl
.pids
.fw_heading
.integral
);
384 DEBUG_SET(DEBUG_NAV_YAW
, 2, posControl
.pids
.fw_heading
.derivative
);
385 DEBUG_SET(DEBUG_NAV_YAW
, 3, navHeadingError
);
386 DEBUG_SET(DEBUG_NAV_YAW
, 4, posControl
.pids
.fw_heading
.output_constrained
);
388 return yawAdjustment
;
391 static void updatePositionHeadingController_FW(timeUs_t currentTimeUs
, timeDelta_t deltaMicros
)
393 static timeUs_t previousTimeMonitoringUpdate
;
394 static int32_t previousHeadingError
;
395 static bool errorIsDecreasing
;
396 static bool forceTurnDirection
= false;
398 if (FLIGHT_MODE(NAV_COURSE_HOLD_MODE
)) {
399 virtualTargetBearing
= posControl
.desiredState
.yaw
;
401 // We have virtual position target, calculate heading error
402 int32_t virtualTargetBearing
= calculateBearingToDestination(&virtualDesiredPosition
);
405 /* If waypoint tracking enabled quickly force craft toward waypoint course line and closely track along it */
406 if (navConfig()->fw
.wp_tracking_accuracy
&& isWaypointNavTrackingActive() && !needToCalculateCircularLoiter
) {
407 // courseVirtualCorrection initially used to determine current position relative to course line for later use
408 int32_t courseVirtualCorrection
= wrap_18000(posControl
.activeWaypoint
.yaw
- virtualTargetBearing
);
409 float distToCourseLine
= ABS(posControl
.wpDistance
* sin_approx(CENTIDEGREES_TO_RADIANS(courseVirtualCorrection
)));
411 // tracking only active when certain distance and heading conditions are met
412 if ((ABS(wrap_18000(virtualTargetBearing
- posControl
.actualState
.yaw
)) < 9000 || posControl
.wpDistance
< 1000.0f
) && distToCourseLine
> 200) {
413 int32_t courseHeadingError
= wrap_18000(posControl
.activeWaypoint
.yaw
- posControl
.actualState
.yaw
);
415 // captureFactor adjusts distance/heading sensitivity balance when closing in on course line.
416 // Closing distance threashold based on speed and an assumed 1 second response time.
417 float captureFactor
= distToCourseLine
< posControl
.actualState
.velXY
? constrainf(2.0f
- ABS(courseHeadingError
) / 500.0f
, 0.0f
, 2.0f
) : 1.0f
;
419 // bias between reducing distance to course line and aligning with course heading adjusted by waypoint_tracking_accuracy
420 // initial courseCorrectionFactor based on distance to course line
421 float courseCorrectionFactor
= constrainf(captureFactor
* distToCourseLine
/ (1000.0f
* navConfig()->fw
.wp_tracking_accuracy
), 0.0f
, 1.0f
);
422 courseCorrectionFactor
= courseVirtualCorrection
< 0 ? -courseCorrectionFactor
: courseCorrectionFactor
;
424 // course heading alignment factor
425 float courseHeadingFactor
= constrainf(courseHeadingError
/ 18000.0f
, 0.0f
, 1.0f
);
426 courseHeadingFactor
= courseHeadingError
< 0 ? -courseHeadingFactor
: courseHeadingFactor
;
428 // final courseCorrectionFactor combining distance and heading factors
429 courseCorrectionFactor
= constrainf(courseCorrectionFactor
- courseHeadingFactor
, -1.0f
, 1.0f
);
431 // final courseVirtualCorrection value
432 courseVirtualCorrection
= DEGREES_TO_CENTIDEGREES(navConfig()->fw
.wp_tracking_max_angle
) * courseCorrectionFactor
;
433 virtualTargetBearing
= wrap_36000(posControl
.activeWaypoint
.yaw
- courseVirtualCorrection
);
438 * Calculate NAV heading error
439 * Units are centidegrees
441 navHeadingError
= wrap_18000(virtualTargetBearing
- posControl
.actualState
.yaw
);
443 // Forced turn direction
444 // If heading error is close to 180 deg we initiate forced turn and only disable it when heading error goes below 90 deg
445 if (ABS(navHeadingError
) > 17000) {
446 forceTurnDirection
= true;
448 else if (ABS(navHeadingError
) < 9000 && forceTurnDirection
) {
449 forceTurnDirection
= false;
452 // If forced turn direction flag is enabled we fix the sign of the direction
453 if (forceTurnDirection
) {
454 navHeadingError
= loiterDirection() * ABS(navHeadingError
);
457 // Slow error monitoring (2Hz rate)
458 if ((currentTimeUs
- previousTimeMonitoringUpdate
) >= HZ2US(NAV_FW_CONTROL_MONITORING_RATE
)) {
459 // Check if error is decreasing over time
460 errorIsDecreasing
= (ABS(previousHeadingError
) > ABS(navHeadingError
));
462 // Save values for next iteration
463 previousHeadingError
= navHeadingError
;
464 previousTimeMonitoringUpdate
= currentTimeUs
;
467 // Only allow PID integrator to shrink if error is decreasing over time
468 const pidControllerFlags_e pidFlags
= PID_DTERM_FROM_ERROR
| (errorIsDecreasing
? PID_SHRINK_INTEGRATOR
: 0);
470 // Input error in (deg*100), output roll angle (deg*100)
471 float rollAdjustment
= navPidApply2(&posControl
.pids
.fw_nav
, posControl
.actualState
.yaw
+ navHeadingError
, posControl
.actualState
.yaw
, US2S(deltaMicros
),
472 -DEGREES_TO_CENTIDEGREES(navConfig()->fw
.max_bank_angle
),
473 DEGREES_TO_CENTIDEGREES(navConfig()->fw
.max_bank_angle
),
476 // Apply low-pass filter to prevent rapid correction
477 rollAdjustment
= pt1FilterApply4(&fwPosControllerCorrectionFilterState
, rollAdjustment
, getSmoothnessCutoffFreq(NAV_FW_BASE_ROLL_CUTOFF_FREQUENCY_HZ
), US2S(deltaMicros
));
479 // Convert rollAdjustment to decidegrees (rcAdjustment holds decidegrees)
480 posControl
.rcAdjustment
[ROLL
] = CENTIDEGREES_TO_DECIDEGREES(rollAdjustment
);
484 * It is working in relative mode and we aim to keep error at zero
486 if (STATE(FW_HEADING_USE_YAW
)) {
487 posControl
.rcAdjustment
[YAW
] = processHeadingYawController(deltaMicros
, navHeadingError
, errorIsDecreasing
);
489 posControl
.rcAdjustment
[YAW
] = 0;
493 void applyFixedWingPositionController(timeUs_t currentTimeUs
)
495 static timeUs_t previousTimePositionUpdate
= 0; // Occurs @ GPS update rate
497 // Apply controller only if position source is valid. In absence of valid pos sensor (GPS loss), we'd stick in forced ANGLE mode
498 if ((posControl
.flags
.estPosStatus
>= EST_USABLE
)) {
499 // If we have new position - update velocity and acceleration controllers
500 if (posControl
.flags
.horizontalPositionDataNew
) {
501 const timeDeltaLarge_t deltaMicrosPositionUpdate
= currentTimeUs
- previousTimePositionUpdate
;
502 previousTimePositionUpdate
= currentTimeUs
;
504 if (deltaMicrosPositionUpdate
< MAX_POSITION_UPDATE_INTERVAL_US
) {
505 // Calculate virtual position target at a distance of forwardVelocity * HZ2S(POSITION_TARGET_UPDATE_RATE_HZ)
506 // Account for pilot's roll input (move position target left/right at max of max_manual_speed)
507 // POSITION_TARGET_UPDATE_RATE_HZ should be chosen keeping in mind that position target shouldn't be reached until next pos update occurs
508 // FIXME: verify the above
509 calculateVirtualPositionTarget_FW(HZ2S(MIN_POSITION_UPDATE_RATE_HZ
) * 2);
511 updatePositionHeadingController_FW(currentTimeUs
, deltaMicrosPositionUpdate
);
514 // Position update has not occurred in time (first iteration or glitch), reset altitude controller
515 resetFixedWingPositionController();
518 // Indicate that information is no longer usable
519 posControl
.flags
.horizontalPositionDataConsumed
= true;
522 isRollAdjustmentValid
= true;
523 isYawAdjustmentValid
= true;
526 // No valid pos sensor data, don't adjust pitch automatically, rcCommand[ROLL] is passed through to PID controller
527 isRollAdjustmentValid
= false;
528 isYawAdjustmentValid
= false;
532 int16_t applyFixedWingMinSpeedController(timeUs_t currentTimeUs
)
534 static timeUs_t previousTimePositionUpdate
= 0; // Occurs @ GPS update rate
536 // Apply controller only if position source is valid
537 if ((posControl
.flags
.estPosStatus
>= EST_USABLE
)) {
538 // If we have new position - update velocity and acceleration controllers
539 if (posControl
.flags
.horizontalPositionDataNew
) {
540 const timeDeltaLarge_t deltaMicrosPositionUpdate
= currentTimeUs
- previousTimePositionUpdate
;
541 previousTimePositionUpdate
= currentTimeUs
;
543 if (deltaMicrosPositionUpdate
< MAX_POSITION_UPDATE_INTERVAL_US
) {
544 float velThrottleBoost
= (NAV_FW_MIN_VEL_SPEED_BOOST
- posControl
.actualState
.velXY
) * NAV_FW_THROTTLE_SPEED_BOOST_GAIN
* US2S(deltaMicrosPositionUpdate
);
546 // If we are in the deadband of 50cm/s - don't update speed boost
547 if (fabsf(posControl
.actualState
.velXY
- NAV_FW_MIN_VEL_SPEED_BOOST
) > 50) {
548 throttleSpeedAdjustment
+= velThrottleBoost
;
551 throttleSpeedAdjustment
= constrainf(throttleSpeedAdjustment
, 0.0f
, 500.0f
);
554 // Position update has not occurred in time (first iteration or glitch), reset altitude controller
555 throttleSpeedAdjustment
= 0;
558 // Indicate that information is no longer usable
559 posControl
.flags
.horizontalPositionDataConsumed
= true;
563 // No valid pos sensor data, we can't calculate speed
564 throttleSpeedAdjustment
= 0;
567 return throttleSpeedAdjustment
;
570 int16_t fixedWingPitchToThrottleCorrection(int16_t pitch
, timeUs_t currentTimeUs
)
572 static timeUs_t previousTimePitchToThrCorr
= 0;
573 const timeDeltaLarge_t deltaMicrosPitchToThrCorr
= currentTimeUs
- previousTimePitchToThrCorr
;
574 previousTimePitchToThrCorr
= currentTimeUs
;
576 static pt1Filter_t pitchToThrFilterState
;
578 // Apply low-pass filter to pitch angle to smooth throttle correction
579 int16_t filteredPitch
= (int16_t)pt1FilterApply4(&pitchToThrFilterState
, pitch
, getPitchToThrottleSmoothnessCutoffFreq(NAV_FW_BASE_PITCH_CUTOFF_FREQUENCY_HZ
), US2S(deltaMicrosPitchToThrCorr
));
581 if (ABS(pitch
- filteredPitch
) > navConfig()->fw
.pitch_to_throttle_thresh
) {
582 // Unfiltered throttle correction outside of pitch deadband
583 return DECIDEGREES_TO_DEGREES(pitch
) * currentBatteryProfile
->nav
.fw
.pitch_to_throttle
;
586 // Filtered throttle correction inside of pitch deadband
587 return DECIDEGREES_TO_DEGREES(filteredPitch
) * currentBatteryProfile
->nav
.fw
.pitch_to_throttle
;
591 void applyFixedWingPitchRollThrottleController(navigationFSMStateFlags_t navStateFlags
, timeUs_t currentTimeUs
)
593 int16_t minThrottleCorrection
= currentBatteryProfile
->nav
.fw
.min_throttle
- currentBatteryProfile
->nav
.fw
.cruise_throttle
;
594 int16_t maxThrottleCorrection
= currentBatteryProfile
->nav
.fw
.max_throttle
- currentBatteryProfile
->nav
.fw
.cruise_throttle
;
596 if (isRollAdjustmentValid
&& (navStateFlags
& NAV_CTL_POS
)) {
597 // ROLL >0 right, <0 left
598 int16_t rollCorrection
= constrain(posControl
.rcAdjustment
[ROLL
], -DEGREES_TO_DECIDEGREES(navConfig()->fw
.max_bank_angle
), DEGREES_TO_DECIDEGREES(navConfig()->fw
.max_bank_angle
));
599 rcCommand
[ROLL
] = pidAngleToRcCommand(rollCorrection
, pidProfile()->max_angle_inclination
[FD_ROLL
]);
602 if (isYawAdjustmentValid
&& (navStateFlags
& NAV_CTL_POS
)) {
603 rcCommand
[YAW
] = posControl
.rcAdjustment
[YAW
];
606 if (isPitchAdjustmentValid
&& (navStateFlags
& NAV_CTL_ALT
)) {
607 // PITCH >0 dive, <0 climb
608 int16_t pitchCorrection
= constrain(posControl
.rcAdjustment
[PITCH
], -DEGREES_TO_DECIDEGREES(navConfig()->fw
.max_dive_angle
), DEGREES_TO_DECIDEGREES(navConfig()->fw
.max_climb_angle
));
609 rcCommand
[PITCH
] = -pidAngleToRcCommand(pitchCorrection
, pidProfile()->max_angle_inclination
[FD_PITCH
]);
610 int16_t throttleCorrection
= fixedWingPitchToThrottleCorrection(pitchCorrection
, currentTimeUs
);
612 #ifdef NAV_FIXED_WING_LANDING
613 if (navStateFlags
& NAV_CTL_LAND
) {
614 // During LAND we do not allow to raise THROTTLE when nose is up to reduce speed
615 throttleCorrection
= constrain(throttleCorrection
, minThrottleCorrection
, 0);
618 throttleCorrection
= constrain(throttleCorrection
, minThrottleCorrection
, maxThrottleCorrection
);
619 #ifdef NAV_FIXED_WING_LANDING
623 // Speed controller - only apply in POS mode when NOT NAV_CTL_LAND
624 if ((navStateFlags
& NAV_CTL_POS
) && !(navStateFlags
& NAV_CTL_LAND
)) {
625 throttleCorrection
+= applyFixedWingMinSpeedController(currentTimeUs
);
626 throttleCorrection
= constrain(throttleCorrection
, minThrottleCorrection
, maxThrottleCorrection
);
629 uint16_t correctedThrottleValue
= constrain(currentBatteryProfile
->nav
.fw
.cruise_throttle
+ throttleCorrection
, currentBatteryProfile
->nav
.fw
.min_throttle
, currentBatteryProfile
->nav
.fw
.max_throttle
);
631 // Manual throttle increase
632 if (navConfig()->fw
.allow_manual_thr_increase
&& !FLIGHT_MODE(FAILSAFE_MODE
)) {
633 if (rcCommand
[THROTTLE
] < PWM_RANGE_MIN
+ (PWM_RANGE_MAX
- PWM_RANGE_MIN
) * 0.95){
634 correctedThrottleValue
+= MAX(0, rcCommand
[THROTTLE
] - currentBatteryProfile
->nav
.fw
.cruise_throttle
);
636 correctedThrottleValue
= motorConfig()->maxthrottle
;
638 isAutoThrottleManuallyIncreased
= (rcCommand
[THROTTLE
] > currentBatteryProfile
->nav
.fw
.cruise_throttle
);
640 isAutoThrottleManuallyIncreased
= false;
643 rcCommand
[THROTTLE
] = constrain(correctedThrottleValue
, getThrottleIdleValue(), motorConfig()->maxthrottle
);
646 #ifdef NAV_FIXED_WING_LANDING
648 * Then altitude is below landing slowdown min. altitude, enable final approach procedure
649 * TODO refactor conditions in this metod if logic is proven to be correct
651 if (navStateFlags
& NAV_CTL_LAND
|| STATE(LANDING_DETECTED
)) {
652 int32_t finalAltitude
= navConfig()->general
.land_slowdown_minalt
+ posControl
.rthState
.homeTmpWaypoint
.z
;
654 if ((posControl
.flags
.estAltStatus
>= EST_USABLE
&& navGetCurrentActualPositionAndVelocity()->pos
.z
<= finalAltitude
) ||
655 (posControl
.flags
.estAglStatus
== EST_TRUSTED
&& posControl
.actualState
.agl
.pos
.z
<= navConfig()->general
.land_slowdown_minalt
)) {
657 // Set motor to min. throttle and stop it when MOTOR_STOP feature is enabled
658 rcCommand
[THROTTLE
] = getThrottleIdleValue();
659 ENABLE_STATE(NAV_MOTOR_STOP_OR_IDLE
);
661 // Stabilize ROLL axis on 0 degrees banking regardless of loiter radius and position
664 // Stabilize PITCH angle into shallow dive as specified by the nav_fw_land_dive_angle setting (default value is 2 - defined in navigation.c).
665 rcCommand
[PITCH
] = pidAngleToRcCommand(DEGREES_TO_DECIDEGREES(navConfig()->fw
.land_dive_angle
), pidProfile()->max_angle_inclination
[FD_PITCH
]);
671 bool isFixedWingAutoThrottleManuallyIncreased()
673 return isAutoThrottleManuallyIncreased
;
676 bool isFixedWingFlying(void)
678 float airspeed
= 0.0f
;
680 airspeed
= getAirspeedEstimate();
682 bool throttleCondition
= getMotorCount() == 0 || rcCommand
[THROTTLE
] > currentBatteryProfile
->nav
.fw
.cruise_throttle
;
683 bool velCondition
= posControl
.actualState
.velXY
> 250.0f
|| airspeed
> 250.0f
;
684 bool launchCondition
= isNavLaunchEnabled() && fixedWingLaunchStatus() == FW_LAUNCH_FLYING
;
686 return (isImuHeadingValid() && throttleCondition
&& velCondition
) || launchCondition
;
689 /*-----------------------------------------------------------
690 * FixedWing land detector
691 *-----------------------------------------------------------*/
692 bool isFixedWingLandingDetected(void)
694 DEBUG_SET(DEBUG_LANDING
, 4, 0);
695 static bool fixAxisCheck
= false;
696 const bool throttleIsLow
= calculateThrottleStatus(THROTTLE_STATUS_TYPE_RC
) == THROTTLE_LOW
;
698 // Basic condition to start looking for landing
699 bool startCondition
= (navGetCurrentStateFlags() & (NAV_CTL_LAND
| NAV_CTL_EMERG
))
700 || FLIGHT_MODE(FAILSAFE_MODE
)
701 || (!navigationIsControllingThrottle() && throttleIsLow
);
703 if (!startCondition
|| posControl
.flags
.resetLandingDetector
) {
704 return fixAxisCheck
= posControl
.flags
.resetLandingDetector
= false;
706 DEBUG_SET(DEBUG_LANDING
, 4, 1);
708 static timeMs_t fwLandingTimerStartAt
;
709 static int16_t fwLandSetRollDatum
;
710 static int16_t fwLandSetPitchDatum
;
711 const float sensitivity
= navConfig()->general
.land_detect_sensitivity
/ 5.0f
;
713 timeMs_t currentTimeMs
= millis();
715 // Check horizontal and vertical velocities are low (cm/s)
716 bool velCondition
= fabsf(navGetCurrentActualPositionAndVelocity()->vel
.z
) < (50.0f
* sensitivity
) &&
717 posControl
.actualState
.velXY
< (100.0f
* sensitivity
);
718 // Check angular rates are low (degs/s)
719 bool gyroCondition
= averageAbsGyroRates() < (2.0f
* sensitivity
);
720 DEBUG_SET(DEBUG_LANDING
, 2, velCondition
);
721 DEBUG_SET(DEBUG_LANDING
, 3, gyroCondition
);
723 if (velCondition
&& gyroCondition
){
724 DEBUG_SET(DEBUG_LANDING
, 4, 2);
725 DEBUG_SET(DEBUG_LANDING
, 5, fixAxisCheck
);
726 if (!fixAxisCheck
) { // capture roll and pitch angles to be used as datums to check for absolute change
727 fwLandSetRollDatum
= attitude
.values
.roll
; //0.1 deg increments
728 fwLandSetPitchDatum
= attitude
.values
.pitch
;
730 fwLandingTimerStartAt
= currentTimeMs
;
732 const uint8_t angleLimit
= 5 * sensitivity
;
733 bool isRollAxisStatic
= ABS(fwLandSetRollDatum
- attitude
.values
.roll
) < angleLimit
;
734 bool isPitchAxisStatic
= ABS(fwLandSetPitchDatum
- attitude
.values
.pitch
) < angleLimit
;
735 DEBUG_SET(DEBUG_LANDING
, 6, isRollAxisStatic
);
736 DEBUG_SET(DEBUG_LANDING
, 7, isPitchAxisStatic
);
737 if (isRollAxisStatic
&& isPitchAxisStatic
) {
738 // Probably landed, low horizontal and vertical velocities and no axis rotation in Roll and Pitch
739 timeMs_t safetyTimeDelay
= 2000 + navConfig()->general
.auto_disarm_delay
;
740 return currentTimeMs
- fwLandingTimerStartAt
> safetyTimeDelay
; // check conditions stable for 2s + optional extra delay
742 fixAxisCheck
= false;
749 /*-----------------------------------------------------------
750 * FixedWing emergency landing
751 *-----------------------------------------------------------*/
752 void applyFixedWingEmergencyLandingController(timeUs_t currentTimeUs
)
754 rcCommand
[ROLL
] = pidAngleToRcCommand(failsafeConfig()->failsafe_fw_roll_angle
, pidProfile()->max_angle_inclination
[FD_ROLL
]);
755 rcCommand
[YAW
] = -pidRateToRcCommand(failsafeConfig()->failsafe_fw_yaw_rate
, currentControlRateProfile
->stabilized
.rates
[FD_YAW
]);
756 rcCommand
[THROTTLE
] = currentBatteryProfile
->failsafe_throttle
;
758 if (posControl
.flags
.estAltStatus
>= EST_USABLE
) {
759 updateClimbRateToAltitudeController(-1.0f
* navConfig()->general
.emerg_descent_rate
, ROC_TO_ALT_NORMAL
);
760 applyFixedWingAltitudeAndThrottleController(currentTimeUs
);
762 int16_t pitchCorrection
= constrain(posControl
.rcAdjustment
[PITCH
], -DEGREES_TO_DECIDEGREES(navConfig()->fw
.max_dive_angle
), DEGREES_TO_DECIDEGREES(navConfig()->fw
.max_climb_angle
));
763 rcCommand
[PITCH
] = -pidAngleToRcCommand(pitchCorrection
, pidProfile()->max_angle_inclination
[FD_PITCH
]);
765 rcCommand
[PITCH
] = pidAngleToRcCommand(failsafeConfig()->failsafe_fw_pitch_angle
, pidProfile()->max_angle_inclination
[FD_PITCH
]);
769 /*-----------------------------------------------------------
770 * Calculate loiter target based on current position and velocity
771 *-----------------------------------------------------------*/
772 void calculateFixedWingInitialHoldPosition(fpVector3_t
* pos
)
774 // TODO: stub, this should account for velocity and target loiter radius
775 *pos
= navGetCurrentActualPositionAndVelocity()->pos
;
778 void resetFixedWingHeadingController(void)
780 updateHeadingHoldTarget(CENTIDEGREES_TO_DEGREES(posControl
.actualState
.yaw
));
783 void applyFixedWingNavigationController(navigationFSMStateFlags_t navStateFlags
, timeUs_t currentTimeUs
)
785 if (navStateFlags
& NAV_CTL_LAUNCH
) {
786 applyFixedWingLaunchController(currentTimeUs
);
788 else if (navStateFlags
& NAV_CTL_EMERG
) {
789 applyFixedWingEmergencyLandingController(currentTimeUs
);
792 #ifdef NAV_FW_LIMIT_MIN_FLY_VELOCITY
793 // Don't apply anything if ground speed is too low (<3m/s)
794 if (posControl
.actualState
.velXY
> 300) {
798 if (navStateFlags
& NAV_CTL_ALT
) {
799 if (getMotorStatus() == MOTOR_STOPPED_USER
|| FLIGHT_MODE(SOARING_MODE
)) {
800 // Motor has been stopped by user or soaring mode enabled to override altitude control
801 resetFixedWingAltitudeController();
802 setDesiredPosition(&navGetCurrentActualPositionAndVelocity()->pos
, posControl
.actualState
.yaw
, NAV_POS_UPDATE_Z
);
804 applyFixedWingAltitudeAndThrottleController(currentTimeUs
);
808 if (navStateFlags
& NAV_CTL_POS
) {
809 applyFixedWingPositionController(currentTimeUs
);
813 posControl
.rcAdjustment
[PITCH
] = 0;
814 posControl
.rcAdjustment
[ROLL
] = 0;
817 if (FLIGHT_MODE(NAV_COURSE_HOLD_MODE
) && posControl
.flags
.isAdjustingPosition
) {
818 rcCommand
[ROLL
] = applyDeadbandRescaled(rcCommand
[ROLL
], rcControlsConfig()->pos_hold_deadband
, -500, 500);
821 //if (navStateFlags & NAV_CTL_YAW)
822 if ((navStateFlags
& NAV_CTL_ALT
) || (navStateFlags
& NAV_CTL_POS
)) {
823 applyFixedWingPitchRollThrottleController(navStateFlags
, currentTimeUs
);
826 if (FLIGHT_MODE(SOARING_MODE
) && navConfig()->general
.flags
.soaring_motor_stop
) {
827 ENABLE_STATE(NAV_MOTOR_STOP_OR_IDLE
);
832 int32_t navigationGetHeadingError(void)
834 return navHeadingError
;