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"
42 #include "flight/mixer_profile.h"
44 #include "fc/config.h"
45 #include "fc/controlrate_profile.h"
46 #include "fc/rc_controls.h"
47 #include "fc/rc_modes.h"
48 #include "fc/runtime_config.h"
50 #include "navigation/navigation.h"
51 #include "navigation/navigation_private.h"
53 #include "programming/logic_condition.h"
57 #include "sensors/battery.h"
59 // Base frequencies for smoothing pitch and roll
60 #define NAV_FW_BASE_PITCH_CUTOFF_FREQUENCY_HZ 2.0f
61 #define NAV_FW_BASE_ROLL_CUTOFF_FREQUENCY_HZ 10.0f
63 // If we are going slower than the minimum ground speed (navConfig()->general.min_ground_speed) - boost throttle to fight against the wind
64 #define NAV_FW_THROTTLE_SPEED_BOOST_GAIN 1.5f
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 float navCrossTrackError
;
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()->fw
.max_manual_climb_rate
/ (500.0f
- rcControlsConfig()->alt_hold_deadband
);
119 updateClimbRateToAltitudeController(rcClimbRate
, 0, ROC_TO_ALT_CONSTANT
);
123 // Adjusting finished - reset desired position to stay exactly where pilot released the stick
124 if (posControl
.flags
.isAdjustingAltitude
) {
125 updateClimbRateToAltitudeController(0, 0, ROC_TO_ALT_CURRENT
);
131 // Position to velocity controller for Z axis
132 static void updateAltitudeVelocityAndPitchController_FW(timeDelta_t deltaMicros
)
134 static pt1Filter_t velzFilterState
;
136 float desiredClimbRate
= getDesiredClimbRate(posControl
.desiredState
.pos
.z
, deltaMicros
);
138 // Reduce max allowed climb rate by 2/3 if performing loiter (stall prevention)
139 if (needToCalculateCircularLoiter
&& desiredClimbRate
> 0.67f
* navConfig()->fw
.max_auto_climb_rate
) {
140 desiredClimbRate
= 0.67f
* navConfig()->fw
.max_auto_climb_rate
;
143 // Here we use negative values for dive for better clarity
144 const float maxClimbDeciDeg
= DEGREES_TO_DECIDEGREES(navConfig()->fw
.max_climb_angle
);
145 const float minDiveDeciDeg
= -DEGREES_TO_DECIDEGREES(navConfig()->fw
.max_dive_angle
);
147 // PID controller to translate desired climb rate error into pitch angle [decideg]
148 float currentClimbRate
= navGetCurrentActualPositionAndVelocity()->vel
.z
;
149 float targetPitchAngle
= navPidApply2(&posControl
.pids
.fw_alt
, desiredClimbRate
, currentClimbRate
, US2S(deltaMicros
), minDiveDeciDeg
, maxClimbDeciDeg
, PID_DTERM_FROM_ERROR
);
151 // Apply low-pass filter to prevent rapid correction
152 targetPitchAngle
= pt1FilterApply4(&velzFilterState
, targetPitchAngle
, getSmoothnessCutoffFreq(NAV_FW_BASE_PITCH_CUTOFF_FREQUENCY_HZ
), US2S(deltaMicros
));
154 // Reconstrain pitch angle (> 0 - climb, < 0 - dive)
155 targetPitchAngle
= constrainf(targetPitchAngle
, minDiveDeciDeg
, maxClimbDeciDeg
);
156 posControl
.rcAdjustment
[PITCH
] = targetPitchAngle
;
158 posControl
.desiredState
.vel
.z
= desiredClimbRate
;
159 navDesiredVelocity
[Z
] = constrain(lrintf(posControl
.desiredState
.vel
.z
), -32678, 32767);
162 void applyFixedWingAltitudeAndThrottleController(timeUs_t currentTimeUs
)
164 static timeUs_t previousTimePositionUpdate
= 0; // Occurs @ altitude sensor update rate (max MAX_ALTITUDE_UPDATE_RATE_HZ)
166 if ((posControl
.flags
.estAltStatus
>= EST_USABLE
)) {
167 if (posControl
.flags
.verticalPositionDataNew
) {
168 const timeDeltaLarge_t deltaMicrosPositionUpdate
= currentTimeUs
- previousTimePositionUpdate
;
169 previousTimePositionUpdate
= currentTimeUs
;
171 // Check if last correction was not too long ago
172 if (deltaMicrosPositionUpdate
< MAX_POSITION_UPDATE_INTERVAL_US
) {
173 updateAltitudeVelocityAndPitchController_FW(deltaMicrosPositionUpdate
);
176 // Position update has not occurred in time (first iteration or glitch), reset altitude controller
177 resetFixedWingAltitudeController();
180 // Indicate that information is no longer usable
181 posControl
.flags
.verticalPositionDataConsumed
= true;
184 isPitchAdjustmentValid
= true;
187 // No valid altitude sensor data, don't adjust pitch automatically, rcCommand[PITCH] is passed through to PID controller
188 isPitchAdjustmentValid
= false;
192 /*-----------------------------------------------------------
193 * Adjusts desired heading from pilot's input
194 *-----------------------------------------------------------*/
195 bool adjustFixedWingHeadingFromRCInput(void)
197 if (ABS(rcCommand
[YAW
]) > rcControlsConfig()->pos_hold_deadband
) {
204 /*-----------------------------------------------------------
205 * XY-position controller for multicopter aircraft
206 *-----------------------------------------------------------*/
207 static fpVector3_t virtualDesiredPosition
;
208 static pt1Filter_t fwPosControllerCorrectionFilterState
;
211 * TODO Currently this function resets both FixedWing and Rover & Boat position controller
213 void resetFixedWingPositionController(void)
215 virtualDesiredPosition
.x
= 0;
216 virtualDesiredPosition
.y
= 0;
217 virtualDesiredPosition
.z
= 0;
219 navPidReset(&posControl
.pids
.fw_nav
);
220 navPidReset(&posControl
.pids
.fw_heading
);
221 posControl
.rcAdjustment
[ROLL
] = 0;
222 posControl
.rcAdjustment
[YAW
] = 0;
223 isRollAdjustmentValid
= false;
224 isYawAdjustmentValid
= false;
226 pt1FilterReset(&fwPosControllerCorrectionFilterState
, 0.0f
);
229 static int8_t loiterDirection(void) {
230 int8_t dir
= 1; //NAV_LOITER_RIGHT
232 if (navConfig()->fw
.loiter_direction
== NAV_LOITER_LEFT
) {
236 if (navConfig()->fw
.loiter_direction
== NAV_LOITER_YAW
) {
238 if (rcCommand
[YAW
] < -250) {
239 loiterDirYaw
= 1; //RIGHT //yaw is contrariwise
242 if (rcCommand
[YAW
] > 250) {
243 loiterDirYaw
= -1; //LEFT //see annexCode in fc_core.c
249 if (IS_RC_MODE_ACTIVE(BOXLOITERDIRCHN
)) {
256 static void calculateVirtualPositionTarget_FW(float trackingPeriod
)
258 if (FLIGHT_MODE(NAV_COURSE_HOLD_MODE
) || posControl
.navState
== NAV_STATE_FW_LANDING_GLIDE
|| posControl
.navState
== NAV_STATE_FW_LANDING_FLARE
) {
262 float posErrorX
= posControl
.desiredState
.pos
.x
- navGetCurrentActualPositionAndVelocity()->pos
.x
;
263 float posErrorY
= posControl
.desiredState
.pos
.y
- navGetCurrentActualPositionAndVelocity()->pos
.y
;
265 float distanceToActualTarget
= calc_length_pythagorean_2D(posErrorX
, posErrorY
);
267 // Limit minimum forward velocity to 1 m/s
268 float trackingDistance
= trackingPeriod
* MAX(posControl
.actualState
.velXY
, 100.0f
);
270 uint32_t navLoiterRadius
= getLoiterRadius(navConfig()->fw
.loiter_radius
);
271 fpVector3_t loiterCenterPos
= posControl
.desiredState
.pos
;
272 int8_t loiterTurnDirection
= loiterDirection();
274 // Detemine if a circular loiter is required.
275 // For waypoints only use circular loiter when angular visibility is > 30 degs, otherwise head straight toward target
276 #define TAN_15DEG 0.26795f
278 bool loiterApproachActive
= isNavHoldPositionActive() &&
279 distanceToActualTarget
<= (navLoiterRadius
/ TAN_15DEG
) &&
280 distanceToActualTarget
> 50.0f
;
281 needToCalculateCircularLoiter
= loiterApproachActive
|| (navGetCurrentStateFlags() & NAV_CTL_HOLD
);
283 //if vtol landing is required, fly straight to homepoint
284 if ((posControl
.navState
== NAV_STATE_RTH_HEAD_HOME
) && navigationRTHAllowsLanding() && checkMixerATRequired(MIXERAT_REQUEST_LAND
)){
285 needToCalculateCircularLoiter
= false;
288 /* WP turn smoothing with 2 options, 1: pass through WP, 2: cut inside turn missing WP
289 * Works for turns > 30 degs and < 160 degs.
290 * Option 1 switches to loiter path around waypoint using navLoiterRadius.
291 * Loiter centered on point inside turn at required distance from waypoint and
292 * on a bearing midway between current and next waypoint course bearings.
293 * Option 2 simply uses a normal turn once the turn initiation point is reached */
294 int32_t waypointTurnAngle
= posControl
.activeWaypoint
.nextTurnAngle
== -1 ? -1 : ABS(posControl
.activeWaypoint
.nextTurnAngle
);
295 posControl
.flags
.wpTurnSmoothingActive
= false;
296 if (waypointTurnAngle
> 3000 && waypointTurnAngle
< 16000 && isWaypointNavTrackingActive() && !needToCalculateCircularLoiter
) {
297 // turnStartFactor adjusts start of loiter based on turn angle
298 float turnStartFactor
;
299 if (navConfig()->fw
.wp_turn_smoothing
== WP_TURN_SMOOTHING_ON
) { // passes through WP
300 turnStartFactor
= waypointTurnAngle
/ 6000.0f
;
301 } else { // // cut inside turn missing WP
302 turnStartFactor
= constrainf(tan_approx(CENTIDEGREES_TO_RADIANS(waypointTurnAngle
/ 2.0f
)), 1.0f
, 2.0f
);
304 // velXY provides additional turn initiation distance based on an assumed 1 second delayed turn response time
305 if (posControl
.wpDistance
< (posControl
.actualState
.velXY
+ navLoiterRadius
* turnStartFactor
)) {
306 if (navConfig()->fw
.wp_turn_smoothing
== WP_TURN_SMOOTHING_ON
) {
307 int32_t loiterCenterBearing
= wrap_36000(((wrap_18000(posControl
.activeWaypoint
.nextTurnAngle
- 18000)) / 2) + posControl
.activeWaypoint
.bearing
+ 18000);
308 loiterCenterPos
.x
= posControl
.activeWaypoint
.pos
.x
+ navLoiterRadius
* cos_approx(CENTIDEGREES_TO_RADIANS(loiterCenterBearing
));
309 loiterCenterPos
.y
= posControl
.activeWaypoint
.pos
.y
+ navLoiterRadius
* sin_approx(CENTIDEGREES_TO_RADIANS(loiterCenterBearing
));
311 posErrorX
= loiterCenterPos
.x
- navGetCurrentActualPositionAndVelocity()->pos
.x
;
312 posErrorY
= loiterCenterPos
.y
- navGetCurrentActualPositionAndVelocity()->pos
.y
;
314 // turn direction to next waypoint
315 loiterTurnDirection
= posControl
.activeWaypoint
.nextTurnAngle
> 0 ? 1 : -1; // 1 = right
317 needToCalculateCircularLoiter
= true;
319 posControl
.flags
.wpTurnSmoothingActive
= true;
323 // We are closing in on a waypoint, calculate circular loiter if required
324 if (needToCalculateCircularLoiter
) {
325 float loiterAngle
= atan2_approx(-posErrorY
, -posErrorX
) + DEGREES_TO_RADIANS(loiterTurnDirection
* 45.0f
);
326 float loiterTargetX
= loiterCenterPos
.x
+ navLoiterRadius
* cos_approx(loiterAngle
);
327 float loiterTargetY
= loiterCenterPos
.y
+ navLoiterRadius
* sin_approx(loiterAngle
);
329 // We have temporary loiter target. Recalculate distance and position error
330 posErrorX
= loiterTargetX
- navGetCurrentActualPositionAndVelocity()->pos
.x
;
331 posErrorY
= loiterTargetY
- navGetCurrentActualPositionAndVelocity()->pos
.y
;
332 distanceToActualTarget
= calc_length_pythagorean_2D(posErrorX
, posErrorY
);
335 // Calculate virtual waypoint
336 virtualDesiredPosition
.x
= navGetCurrentActualPositionAndVelocity()->pos
.x
+ posErrorX
* (trackingDistance
/ distanceToActualTarget
);
337 virtualDesiredPosition
.y
= navGetCurrentActualPositionAndVelocity()->pos
.y
+ posErrorY
* (trackingDistance
/ distanceToActualTarget
);
339 // Shift position according to pilot's ROLL input (up to max_manual_speed velocity)
340 if (posControl
.flags
.isAdjustingPosition
) {
341 int16_t rcRollAdjustment
= applyDeadbandRescaled(rcCommand
[ROLL
], rcControlsConfig()->pos_hold_deadband
, -500, 500);
343 if (rcRollAdjustment
) {
344 float rcShiftY
= rcRollAdjustment
* navConfig()->general
.max_manual_speed
/ 500.0f
* trackingPeriod
;
346 // Rotate this target shift from body frame to to earth frame and apply to position target
347 virtualDesiredPosition
.x
+= -rcShiftY
* posControl
.actualState
.sinYaw
;
348 virtualDesiredPosition
.y
+= rcShiftY
* posControl
.actualState
.cosYaw
;
353 bool adjustFixedWingPositionFromRCInput(void)
355 int16_t rcRollAdjustment
= applyDeadbandRescaled(rcCommand
[ROLL
], rcControlsConfig()->pos_hold_deadband
, -500, 500);
356 return (rcRollAdjustment
);
359 float processHeadingYawController(timeDelta_t deltaMicros
, int32_t navHeadingError
, bool errorIsDecreasing
) {
360 static float limit
= 0.0f
;
363 limit
= pidProfile()->navFwPosHdgPidsumLimit
* 100.0f
;
366 const pidControllerFlags_e yawPidFlags
= errorIsDecreasing
? PID_SHRINK_INTEGRATOR
: 0;
368 const float yawAdjustment
= navPidApply2(
369 &posControl
.pids
.fw_heading
,
371 applyDeadband(navHeadingError
, navConfig()->fw
.yawControlDeadband
* 100),
378 DEBUG_SET(DEBUG_NAV_YAW
, 0, posControl
.pids
.fw_heading
.proportional
);
379 DEBUG_SET(DEBUG_NAV_YAW
, 1, posControl
.pids
.fw_heading
.integral
);
380 DEBUG_SET(DEBUG_NAV_YAW
, 2, posControl
.pids
.fw_heading
.derivative
);
381 DEBUG_SET(DEBUG_NAV_YAW
, 3, navHeadingError
);
382 DEBUG_SET(DEBUG_NAV_YAW
, 4, posControl
.pids
.fw_heading
.output_constrained
);
384 return yawAdjustment
;
387 static void updatePositionHeadingController_FW(timeUs_t currentTimeUs
, timeDelta_t deltaMicros
)
389 static timeUs_t previousTimeMonitoringUpdate
;
390 static int32_t previousHeadingError
;
391 static bool errorIsDecreasing
;
392 static bool forceTurnDirection
= false;
393 int32_t virtualTargetBearing
;
395 if (FLIGHT_MODE(NAV_COURSE_HOLD_MODE
) || posControl
.navState
== NAV_STATE_FW_LANDING_GLIDE
|| posControl
.navState
== NAV_STATE_FW_LANDING_FLARE
) {
396 virtualTargetBearing
= posControl
.desiredState
.yaw
;
398 // We have virtual position target, calculate heading error
399 virtualTargetBearing
= calculateBearingToDestination(&virtualDesiredPosition
);
402 /* Calculate cross track error */
403 fpVector3_t virtualCoursePoint
;
404 virtualCoursePoint
.x
= posControl
.activeWaypoint
.pos
.x
-
405 posControl
.wpDistance
* cos_approx(CENTIDEGREES_TO_RADIANS(posControl
.activeWaypoint
.bearing
));
406 virtualCoursePoint
.y
= posControl
.activeWaypoint
.pos
.y
-
407 posControl
.wpDistance
* sin_approx(CENTIDEGREES_TO_RADIANS(posControl
.activeWaypoint
.bearing
));
408 navCrossTrackError
= calculateDistanceToDestination(&virtualCoursePoint
);
410 /* If waypoint tracking enabled force craft toward and closely track along waypoint course line */
411 if (navConfig()->fw
.wp_tracking_accuracy
&& isWaypointNavTrackingActive() && !needToCalculateCircularLoiter
) {
412 static float crossTrackErrorRate
;
413 static timeUs_t previousCrossTrackErrorUpdateTime
;
414 static float previousCrossTrackError
= 0.0f
;
415 static pt1Filter_t fwCrossTrackErrorRateFilterState
;
417 if ((currentTimeUs
- previousCrossTrackErrorUpdateTime
) >= HZ2US(20) && fabsf(previousCrossTrackError
- navCrossTrackError
) > 10.0f
) {
418 const float crossTrackErrorDtSec
= US2S(currentTimeUs
- previousCrossTrackErrorUpdateTime
);
419 if (fabsf(previousCrossTrackError
- navCrossTrackError
) < 500.0f
) {
420 crossTrackErrorRate
= (previousCrossTrackError
- navCrossTrackError
) / crossTrackErrorDtSec
;
422 crossTrackErrorRate
= pt1FilterApply4(&fwCrossTrackErrorRateFilterState
, crossTrackErrorRate
, 3.0f
, crossTrackErrorDtSec
);
423 previousCrossTrackErrorUpdateTime
= currentTimeUs
;
424 previousCrossTrackError
= navCrossTrackError
;
427 uint16_t trackingDeadband
= METERS_TO_CENTIMETERS(navConfig()->fw
.wp_tracking_accuracy
);
429 if ((ABS(wrap_18000(virtualTargetBearing
- posControl
.actualState
.cog
)) < 9000 || posControl
.wpDistance
< 1000.0f
) && navCrossTrackError
> trackingDeadband
) {
430 float adjustmentFactor
= wrap_18000(posControl
.activeWaypoint
.bearing
- virtualTargetBearing
);
431 uint16_t angleLimit
= DEGREES_TO_CENTIDEGREES(navConfig()->fw
.wp_tracking_max_angle
);
433 /* Apply heading adjustment to match crossTrackErrorRate with fixed convergence speed profile */
434 float maxApproachSpeed
= posControl
.actualState
.velXY
* sin_approx(CENTIDEGREES_TO_RADIANS(angleLimit
));
435 float desiredApproachSpeed
= constrainf(navCrossTrackError
/ 3.0f
, 50.0f
, maxApproachSpeed
);
436 adjustmentFactor
= SIGN(adjustmentFactor
) * navCrossTrackError
* ((desiredApproachSpeed
- crossTrackErrorRate
) / desiredApproachSpeed
);
438 /* Calculate final adjusted virtualTargetBearing */
439 uint16_t limit
= constrainf(navCrossTrackError
, 1000.0f
, angleLimit
);
440 adjustmentFactor
= constrainf(adjustmentFactor
, -limit
, limit
);
441 virtualTargetBearing
= wrap_36000(posControl
.activeWaypoint
.bearing
- adjustmentFactor
);
446 * Calculate NAV heading error
447 * Units are centidegrees
449 int32_t navHeadingError
= wrap_18000(virtualTargetBearing
- posControl
.actualState
.cog
);
451 // Forced turn direction
452 // If heading error is close to 180 deg we initiate forced turn and only disable it when heading error goes below 90 deg
453 if (ABS(navHeadingError
) > 17000) {
454 forceTurnDirection
= true;
456 else if (ABS(navHeadingError
) < 9000 && forceTurnDirection
) {
457 forceTurnDirection
= false;
460 // If forced turn direction flag is enabled we fix the sign of the direction
461 if (forceTurnDirection
) {
462 navHeadingError
= loiterDirection() * ABS(navHeadingError
);
465 // Slow error monitoring (2Hz rate)
466 if ((currentTimeUs
- previousTimeMonitoringUpdate
) >= HZ2US(NAV_FW_CONTROL_MONITORING_RATE
)) {
467 // Check if error is decreasing over time
468 errorIsDecreasing
= (ABS(previousHeadingError
) > ABS(navHeadingError
));
470 // Save values for next iteration
471 previousHeadingError
= navHeadingError
;
472 previousTimeMonitoringUpdate
= currentTimeUs
;
475 // Only allow PID integrator to shrink if error is decreasing over time
476 const pidControllerFlags_e pidFlags
= PID_DTERM_FROM_ERROR
| (errorIsDecreasing
? PID_SHRINK_INTEGRATOR
: 0);
478 // Input error in (deg*100), output roll angle (deg*100)
479 float rollAdjustment
= navPidApply2(&posControl
.pids
.fw_nav
, posControl
.actualState
.cog
+ navHeadingError
, posControl
.actualState
.cog
, US2S(deltaMicros
),
480 -DEGREES_TO_CENTIDEGREES(navConfig()->fw
.max_bank_angle
),
481 DEGREES_TO_CENTIDEGREES(navConfig()->fw
.max_bank_angle
),
484 // Apply low-pass filter to prevent rapid correction
485 rollAdjustment
= pt1FilterApply4(&fwPosControllerCorrectionFilterState
, rollAdjustment
, getSmoothnessCutoffFreq(NAV_FW_BASE_ROLL_CUTOFF_FREQUENCY_HZ
), US2S(deltaMicros
));
487 // Convert rollAdjustment to decidegrees (rcAdjustment holds decidegrees)
488 posControl
.rcAdjustment
[ROLL
] = CENTIDEGREES_TO_DECIDEGREES(rollAdjustment
);
492 * It is working in relative mode and we aim to keep error at zero
494 if (STATE(FW_HEADING_USE_YAW
)) {
495 posControl
.rcAdjustment
[YAW
] = processHeadingYawController(deltaMicros
, navHeadingError
, errorIsDecreasing
);
497 posControl
.rcAdjustment
[YAW
] = 0;
501 void applyFixedWingPositionController(timeUs_t currentTimeUs
)
503 static timeUs_t previousTimePositionUpdate
= 0; // Occurs @ GPS update rate
505 // Apply controller only if position source is valid. In absence of valid pos sensor (GPS loss), we'd stick in forced ANGLE mode
506 if ((posControl
.flags
.estPosStatus
>= EST_USABLE
)) {
507 // If we have new position - update velocity and acceleration controllers
508 if (posControl
.flags
.horizontalPositionDataNew
) {
509 const timeDeltaLarge_t deltaMicrosPositionUpdate
= currentTimeUs
- previousTimePositionUpdate
;
510 previousTimePositionUpdate
= currentTimeUs
;
512 if (deltaMicrosPositionUpdate
< MAX_POSITION_UPDATE_INTERVAL_US
) {
513 // Calculate virtual position target at a distance of forwardVelocity * HZ2S(POSITION_TARGET_UPDATE_RATE_HZ)
514 // Account for pilot's roll input (move position target left/right at max of max_manual_speed)
515 // POSITION_TARGET_UPDATE_RATE_HZ should be chosen keeping in mind that position target shouldn't be reached until next pos update occurs
516 // FIXME: verify the above
517 calculateVirtualPositionTarget_FW(HZ2S(MIN_POSITION_UPDATE_RATE_HZ
) * 2);
518 updatePositionHeadingController_FW(currentTimeUs
, deltaMicrosPositionUpdate
);
519 needToCalculateCircularLoiter
= false;
522 // Position update has not occurred in time (first iteration or glitch), reset altitude controller
523 resetFixedWingPositionController();
526 // Indicate that information is no longer usable
527 posControl
.flags
.horizontalPositionDataConsumed
= true;
530 isRollAdjustmentValid
= true;
531 isYawAdjustmentValid
= true;
534 // No valid pos sensor data, don't adjust pitch automatically, rcCommand[ROLL] is passed through to PID controller
535 isRollAdjustmentValid
= false;
536 isYawAdjustmentValid
= false;
540 int16_t applyFixedWingMinSpeedController(timeUs_t currentTimeUs
)
542 static timeUs_t previousTimePositionUpdate
= 0; // Occurs @ GPS update rate
544 // Apply controller only if position source is valid
545 if ((posControl
.flags
.estPosStatus
>= EST_USABLE
)) {
546 // If we have new position - update velocity and acceleration controllers
547 if (posControl
.flags
.horizontalPositionDataNew
) {
548 const timeDeltaLarge_t deltaMicrosPositionUpdate
= currentTimeUs
- previousTimePositionUpdate
;
549 previousTimePositionUpdate
= currentTimeUs
;
551 if (deltaMicrosPositionUpdate
< MAX_POSITION_UPDATE_INTERVAL_US
) {
552 float velThrottleBoost
= ((navConfig()->general
.min_ground_speed
* 100.0f
) - posControl
.actualState
.velXY
) * NAV_FW_THROTTLE_SPEED_BOOST_GAIN
* US2S(deltaMicrosPositionUpdate
);
554 // If we are in the deadband of 50cm/s - don't update speed boost
555 if (fabsf(posControl
.actualState
.velXY
- (navConfig()->general
.min_ground_speed
* 100.0f
)) > 50) {
556 throttleSpeedAdjustment
+= velThrottleBoost
;
559 throttleSpeedAdjustment
= constrainf(throttleSpeedAdjustment
, 0.0f
, 500.0f
);
562 // Position update has not occurred in time (first iteration or glitch), reset altitude controller
563 throttleSpeedAdjustment
= 0;
566 // Indicate that information is no longer usable
567 posControl
.flags
.horizontalPositionDataConsumed
= true;
571 // No valid pos sensor data, we can't calculate speed
572 throttleSpeedAdjustment
= 0;
575 return throttleSpeedAdjustment
;
578 int16_t fixedWingPitchToThrottleCorrection(int16_t pitch
, timeUs_t currentTimeUs
)
580 static timeUs_t previousTimePitchToThrCorr
= 0;
581 const timeDeltaLarge_t deltaMicrosPitchToThrCorr
= currentTimeUs
- previousTimePitchToThrCorr
;
582 previousTimePitchToThrCorr
= currentTimeUs
;
584 static pt1Filter_t pitchToThrFilterState
;
586 // Apply low-pass filter to pitch angle to smooth throttle correction
587 int16_t filteredPitch
= (int16_t)pt1FilterApply4(&pitchToThrFilterState
, pitch
, getPitchToThrottleSmoothnessCutoffFreq(NAV_FW_BASE_PITCH_CUTOFF_FREQUENCY_HZ
), US2S(deltaMicrosPitchToThrCorr
));
589 int16_t pitchToThrottle
= currentBatteryProfile
->nav
.fw
.pitch_to_throttle
;
591 #ifdef USE_FW_AUTOLAND
592 if (pitch
< 0 && posControl
.fwLandState
.landState
== FW_AUTOLAND_STATE_FINAL_APPROACH
) {
593 pitchToThrottle
*= navFwAutolandConfig()->finalApproachPitchToThrottleMod
/ 100.0f
;
597 if (ABS(pitch
- filteredPitch
) > navConfig()->fw
.pitch_to_throttle_thresh
) {
598 // Unfiltered throttle correction outside of pitch deadband
599 return DECIDEGREES_TO_DEGREES(pitch
) * pitchToThrottle
;
602 // Filtered throttle correction inside of pitch deadband
603 return DECIDEGREES_TO_DEGREES(filteredPitch
) * pitchToThrottle
;
607 void applyFixedWingPitchRollThrottleController(navigationFSMStateFlags_t navStateFlags
, timeUs_t currentTimeUs
)
609 int16_t minThrottleCorrection
= currentBatteryProfile
->nav
.fw
.min_throttle
- currentBatteryProfile
->nav
.fw
.cruise_throttle
;
610 int16_t maxThrottleCorrection
= currentBatteryProfile
->nav
.fw
.max_throttle
- currentBatteryProfile
->nav
.fw
.cruise_throttle
;
612 if (isRollAdjustmentValid
&& (navStateFlags
& NAV_CTL_POS
)) {
613 // ROLL >0 right, <0 left
614 int16_t rollCorrection
= constrain(posControl
.rcAdjustment
[ROLL
], -DEGREES_TO_DECIDEGREES(navConfig()->fw
.max_bank_angle
), DEGREES_TO_DECIDEGREES(navConfig()->fw
.max_bank_angle
));
615 rcCommand
[ROLL
] = pidAngleToRcCommand(rollCorrection
, pidProfile()->max_angle_inclination
[FD_ROLL
]);
618 if (isYawAdjustmentValid
&& (navStateFlags
& NAV_CTL_POS
)) {
619 rcCommand
[YAW
] = posControl
.rcAdjustment
[YAW
];
622 if (isPitchAdjustmentValid
&& (navStateFlags
& NAV_CTL_ALT
)) {
623 // PITCH >0 dive, <0 climb
624 int16_t pitchCorrection
= constrain(posControl
.rcAdjustment
[PITCH
], -DEGREES_TO_DECIDEGREES(navConfig()->fw
.max_dive_angle
), DEGREES_TO_DECIDEGREES(navConfig()->fw
.max_climb_angle
));
625 rcCommand
[PITCH
] = -pidAngleToRcCommand(pitchCorrection
, pidProfile()->max_angle_inclination
[FD_PITCH
]);
626 int16_t throttleCorrection
= fixedWingPitchToThrottleCorrection(pitchCorrection
, currentTimeUs
);
628 if (navStateFlags
& NAV_CTL_LAND
) {
629 // During LAND we do not allow to raise THROTTLE when nose is up to reduce speed
630 throttleCorrection
= constrain(throttleCorrection
, minThrottleCorrection
, 0);
632 throttleCorrection
= constrain(throttleCorrection
, minThrottleCorrection
, maxThrottleCorrection
);
635 // Speed controller - only apply in POS mode when NOT NAV_CTL_LAND
636 if ((navStateFlags
& NAV_CTL_POS
) && !(navStateFlags
& NAV_CTL_LAND
)) {
637 throttleCorrection
+= applyFixedWingMinSpeedController(currentTimeUs
);
638 throttleCorrection
= constrain(throttleCorrection
, minThrottleCorrection
, maxThrottleCorrection
);
641 uint16_t correctedThrottleValue
= constrain(currentBatteryProfile
->nav
.fw
.cruise_throttle
+ throttleCorrection
, currentBatteryProfile
->nav
.fw
.min_throttle
, currentBatteryProfile
->nav
.fw
.max_throttle
);
643 // Manual throttle increase
644 if (navConfig()->fw
.allow_manual_thr_increase
&& !FLIGHT_MODE(FAILSAFE_MODE
) && !FLIGHT_MODE(NAV_FW_AUTOLAND
)) {
645 if (rcCommand
[THROTTLE
] < PWM_RANGE_MIN
+ (PWM_RANGE_MAX
- PWM_RANGE_MIN
) * 0.95){
646 correctedThrottleValue
+= MAX(0, rcCommand
[THROTTLE
] - currentBatteryProfile
->nav
.fw
.cruise_throttle
);
648 correctedThrottleValue
= getMaxThrottle();
650 isAutoThrottleManuallyIncreased
= (rcCommand
[THROTTLE
] > currentBatteryProfile
->nav
.fw
.cruise_throttle
);
652 isAutoThrottleManuallyIncreased
= false;
655 rcCommand
[THROTTLE
] = setDesiredThrottle(correctedThrottleValue
, false);
658 #ifdef USE_FW_AUTOLAND
660 if (posControl
.navState
== NAV_STATE_FW_LANDING_GLIDE
|| posControl
.navState
== NAV_STATE_FW_LANDING_FLARE
|| STATE(LANDING_DETECTED
)) {
661 // Set motor to min. throttle and stop it when MOTOR_STOP feature is enabled
662 ENABLE_STATE(NAV_MOTOR_STOP_OR_IDLE
);
664 if (posControl
.navState
== NAV_STATE_FW_LANDING_GLIDE
) {
665 rcCommand
[PITCH
] = pidAngleToRcCommand(-DEGREES_TO_DECIDEGREES(navFwAutolandConfig()->glidePitch
), pidProfile()->max_angle_inclination
[FD_PITCH
]);
668 if (posControl
.navState
== NAV_STATE_FW_LANDING_FLARE
) {
669 rcCommand
[PITCH
] = pidAngleToRcCommand(-DEGREES_TO_DECIDEGREES(navFwAutolandConfig()->flarePitch
), pidProfile()->max_angle_inclination
[FD_PITCH
]);
673 // "Traditional" landing as fallback option
674 if (navStateFlags
& NAV_CTL_LAND
) {
675 int32_t finalAltitude
= navConfig()->general
.land_slowdown_minalt
+ posControl
.rthState
.homeTmpWaypoint
.z
;
677 if ((posControl
.flags
.estAltStatus
>= EST_USABLE
&& navGetCurrentActualPositionAndVelocity()->pos
.z
<= finalAltitude
) ||
678 (posControl
.flags
.estAglStatus
== EST_TRUSTED
&& posControl
.actualState
.agl
.pos
.z
<= navConfig()->general
.land_slowdown_minalt
)) {
680 // Set motor to min. throttle and stop it when MOTOR_STOP feature is enabled
681 ENABLE_STATE(NAV_MOTOR_STOP_OR_IDLE
);
683 // Stabilize ROLL axis on 0 degrees banking regardless of loiter radius and position
686 // Stabilize PITCH angle into shallow dive as specified by the nav_fw_land_dive_angle setting (default value is 2 - defined in navigation.c).
687 rcCommand
[PITCH
] = pidAngleToRcCommand(DEGREES_TO_DECIDEGREES(navConfig()->fw
.land_dive_angle
), pidProfile()->max_angle_inclination
[FD_PITCH
]);
692 bool isFixedWingAutoThrottleManuallyIncreased(void)
694 return isAutoThrottleManuallyIncreased
;
697 bool isFixedWingFlying(void)
699 float airspeed
= 0.0f
;
701 if (sensors(SENSOR_PITOT
) && pitotIsHealthy()) {
702 airspeed
= getAirspeedEstimate();
705 bool throttleCondition
= getMotorCount() == 0 || rcCommand
[THROTTLE
] > currentBatteryProfile
->nav
.fw
.cruise_throttle
;
706 bool velCondition
= posControl
.actualState
.velXY
> 250.0f
|| airspeed
> 250.0f
;
707 bool launchCondition
= isNavLaunchEnabled() && fixedWingLaunchStatus() == FW_LAUNCH_FLYING
;
709 return (isGPSHeadingValid() && throttleCondition
&& velCondition
) || launchCondition
;
712 /*-----------------------------------------------------------
713 * FixedWing land detector
714 *-----------------------------------------------------------*/
715 bool isFixedWingLandingDetected(void)
717 DEBUG_SET(DEBUG_LANDING
, 4, 0);
718 static bool fixAxisCheck
= false;
720 // Basic condition to start looking for landing
721 bool startCondition
= (navGetCurrentStateFlags() & (NAV_CTL_LAND
| NAV_CTL_EMERG
))
722 || FLIGHT_MODE(FAILSAFE_MODE
)
723 || FLIGHT_MODE(NAV_FW_AUTOLAND
)
724 || (!navigationIsControllingThrottle() && throttleStickIsLow());
726 if (!startCondition
|| posControl
.flags
.resetLandingDetector
) {
727 return fixAxisCheck
= posControl
.flags
.resetLandingDetector
= false;
729 DEBUG_SET(DEBUG_LANDING
, 4, 1);
731 static timeMs_t fwLandingTimerStartAt
;
732 static int16_t fwLandSetRollDatum
;
733 static int16_t fwLandSetPitchDatum
;
734 const float sensitivity
= navConfig()->general
.land_detect_sensitivity
/ 5.0f
;
736 const timeMs_t currentTimeMs
= millis();
738 // Check horizontal and vertical velocities are low (cm/s)
739 bool velCondition
= fabsf(navGetCurrentActualPositionAndVelocity()->vel
.z
) < (50.0f
* sensitivity
) &&
740 ( posControl
.actualState
.velXY
< (100.0f
* sensitivity
));
741 // Check angular rates are low (degs/s)
742 bool gyroCondition
= averageAbsGyroRates() < (2.0f
* sensitivity
);
743 DEBUG_SET(DEBUG_LANDING
, 2, velCondition
);
744 DEBUG_SET(DEBUG_LANDING
, 3, gyroCondition
);
746 if (velCondition
&& gyroCondition
){
747 DEBUG_SET(DEBUG_LANDING
, 4, 2);
748 DEBUG_SET(DEBUG_LANDING
, 5, fixAxisCheck
);
749 if (!fixAxisCheck
) { // capture roll and pitch angles to be used as datums to check for absolute change
750 fwLandSetRollDatum
= attitude
.values
.roll
; //0.1 deg increments
751 fwLandSetPitchDatum
= attitude
.values
.pitch
;
753 fwLandingTimerStartAt
= currentTimeMs
;
755 const uint8_t angleLimit
= 5 * sensitivity
;
756 bool isRollAxisStatic
= ABS(fwLandSetRollDatum
- attitude
.values
.roll
) < angleLimit
;
757 bool isPitchAxisStatic
= ABS(fwLandSetPitchDatum
- attitude
.values
.pitch
) < angleLimit
;
758 DEBUG_SET(DEBUG_LANDING
, 6, isRollAxisStatic
);
759 DEBUG_SET(DEBUG_LANDING
, 7, isPitchAxisStatic
);
760 if (isRollAxisStatic
&& isPitchAxisStatic
) {
761 /* Probably landed, low horizontal and vertical velocities and no axis rotation in Roll and Pitch
762 * Conditions need to be held for fixed safety time + optional extra delay.
763 * Fixed time increased if velocities invalid to provide extra safety margin against false triggers */
764 const uint16_t safetyTime
= posControl
.flags
.estAltStatus
== EST_NONE
|| posControl
.flags
.estVelStatus
== EST_NONE
? 5000 : 1000;
765 timeMs_t safetyTimeDelay
= safetyTime
+ navConfig()->general
.auto_disarm_delay
;
766 return currentTimeMs
- fwLandingTimerStartAt
> safetyTimeDelay
;
768 fixAxisCheck
= false;
775 /*-----------------------------------------------------------
776 * FixedWing emergency landing
777 *-----------------------------------------------------------*/
778 void applyFixedWingEmergencyLandingController(timeUs_t currentTimeUs
)
780 rcCommand
[THROTTLE
] = setDesiredThrottle(currentBatteryProfile
->failsafe_throttle
, true);
782 if (posControl
.flags
.estAltStatus
>= EST_USABLE
) {
783 // target min descent rate at distance 2 x emerg descent rate above takeoff altitude
784 updateClimbRateToAltitudeController(0, 2.0f
* navConfig()->general
.emerg_descent_rate
, ROC_TO_ALT_TARGET
);
785 applyFixedWingAltitudeAndThrottleController(currentTimeUs
);
787 int16_t pitchCorrection
= constrain(posControl
.rcAdjustment
[PITCH
], -DEGREES_TO_DECIDEGREES(navConfig()->fw
.max_dive_angle
), DEGREES_TO_DECIDEGREES(navConfig()->fw
.max_climb_angle
));
788 rcCommand
[PITCH
] = -pidAngleToRcCommand(pitchCorrection
, pidProfile()->max_angle_inclination
[FD_PITCH
]);
790 rcCommand
[PITCH
] = pidAngleToRcCommand(failsafeConfig()->failsafe_fw_pitch_angle
, pidProfile()->max_angle_inclination
[FD_PITCH
]);
793 if (posControl
.flags
.estPosStatus
>= EST_USABLE
) { // Hold position if possible
794 applyFixedWingPositionController(currentTimeUs
);
795 int16_t rollCorrection
= constrain(posControl
.rcAdjustment
[ROLL
],
796 -DEGREES_TO_DECIDEGREES(navConfig()->fw
.max_bank_angle
),
797 DEGREES_TO_DECIDEGREES(navConfig()->fw
.max_bank_angle
));
798 rcCommand
[ROLL
] = pidAngleToRcCommand(rollCorrection
, pidProfile()->max_angle_inclination
[FD_ROLL
]);
801 rcCommand
[ROLL
] = pidAngleToRcCommand(failsafeConfig()->failsafe_fw_roll_angle
, pidProfile()->max_angle_inclination
[FD_ROLL
]);
802 rcCommand
[YAW
] = -pidRateToRcCommand(failsafeConfig()->failsafe_fw_yaw_rate
, currentControlRateProfile
->stabilized
.rates
[FD_YAW
]);
806 /*-----------------------------------------------------------
807 * Calculate loiter target based on current position and velocity
808 *-----------------------------------------------------------*/
809 void calculateFixedWingInitialHoldPosition(fpVector3_t
* pos
)
811 // TODO: stub, this should account for velocity and target loiter radius
812 *pos
= navGetCurrentActualPositionAndVelocity()->pos
;
815 void resetFixedWingHeadingController(void)
817 updateHeadingHoldTarget(CENTIDEGREES_TO_DEGREES(posControl
.actualState
.cog
));
820 void applyFixedWingNavigationController(navigationFSMStateFlags_t navStateFlags
, timeUs_t currentTimeUs
)
822 if (navStateFlags
& NAV_CTL_LAUNCH
) {
823 applyFixedWingLaunchController(currentTimeUs
);
825 else if (navStateFlags
& NAV_CTL_EMERG
) {
826 applyFixedWingEmergencyLandingController(currentTimeUs
);
829 #ifdef NAV_FW_LIMIT_MIN_FLY_VELOCITY
830 // Don't apply anything if ground speed is too low (<3m/s)
831 if (posControl
.actualState
.velXY
> 300) {
835 if (navStateFlags
& NAV_CTL_ALT
) {
836 if (getMotorStatus() == MOTOR_STOPPED_USER
|| FLIGHT_MODE(SOARING_MODE
)) {
837 // Motor has been stopped by user or soaring mode enabled to override altitude control
838 resetFixedWingAltitudeController();
839 setDesiredPosition(&navGetCurrentActualPositionAndVelocity()->pos
, posControl
.actualState
.yaw
, NAV_POS_UPDATE_Z
);
841 applyFixedWingAltitudeAndThrottleController(currentTimeUs
);
845 if (navStateFlags
& NAV_CTL_POS
) {
846 applyFixedWingPositionController(currentTimeUs
);
850 posControl
.rcAdjustment
[PITCH
] = 0;
851 posControl
.rcAdjustment
[ROLL
] = 0;
854 if (FLIGHT_MODE(NAV_COURSE_HOLD_MODE
) && posControl
.flags
.isAdjustingPosition
) {
855 rcCommand
[ROLL
] = applyDeadbandRescaled(rcCommand
[ROLL
], rcControlsConfig()->pos_hold_deadband
, -500, 500);
858 //if (navStateFlags & NAV_CTL_YAW)
859 if ((navStateFlags
& NAV_CTL_ALT
) || (navStateFlags
& NAV_CTL_POS
)) {
860 applyFixedWingPitchRollThrottleController(navStateFlags
, currentTimeUs
);
863 if (FLIGHT_MODE(SOARING_MODE
) && navConfig()->general
.flags
.soaring_motor_stop
) {
864 ENABLE_STATE(NAV_MOTOR_STOP_OR_IDLE
);
869 float navigationGetCrossTrackError(void)
871 return navCrossTrackError
;