AP_Networking: add timeout to swap the UDP Server client target
[ardupilot.git] / ArduPlane / quadplane.cpp
blobd2f74a5b55312800e0218cec0fc26ec24b2ff186
1 #include "Plane.h"
3 #if HAL_QUADPLANE_ENABLED
5 #include "AC_AttitudeControl/AC_AttitudeControl_TS.h"
7 const AP_Param::GroupInfo QuadPlane::var_info[] = {
9 // @Param: ENABLE
10 // @DisplayName: Enable QuadPlane
11 // @Description: This enables QuadPlane functionality, assuming multicopter motors start on output 5. If this is set to 2 then when starting AUTO mode it will initially be in VTOL AUTO mode.
12 // @Values: 0:Disable,1:Enable,2:Enable VTOL AUTO
13 // @User: Standard
14 // @RebootRequired: True
15 AP_GROUPINFO_FLAGS("ENABLE", 1, QuadPlane, enable, 0, AP_PARAM_FLAG_ENABLE),
17 // @Group: M_
18 // @Path: ../libraries/AP_Motors/AP_MotorsMulticopter.cpp
19 AP_SUBGROUPVARPTR(motors, "M_", 2, QuadPlane, plane.quadplane.motors_var_info),
21 // 3 ~ 8 were used by quadplane attitude control PIDs
23 // @Param: ANGLE_MAX
24 // @DisplayName: Angle Max
25 // @Description: Maximum lean angle in all VTOL flight modes
26 // @Units: cdeg
27 // @Increment: 10
28 // @Range: 1000 8000
29 // @User: Advanced
30 AP_GROUPINFO("ANGLE_MAX", 10, QuadPlane, aparm.angle_max, 3000),
32 // @Param: TRANSITION_MS
33 // @DisplayName: Transition time
34 // @Description: Transition time in milliseconds after minimum airspeed is reached
35 // @Units: ms
36 // @Range: 500 30000
37 // @User: Advanced
38 AP_GROUPINFO("TRANSITION_MS", 11, QuadPlane, transition_time_ms, 5000),
40 // 12 ~ 16 were used by position, velocity and acceleration PIDs
42 // @Group: P
43 // @Path: ../libraries/AC_AttitudeControl/AC_PosControl.cpp
44 AP_SUBGROUPPTR(pos_control, "P", 17, QuadPlane, AC_PosControl),
46 // @Param: PILOT_SPD_UP
47 // @DisplayName: Pilot maximum vertical speed up
48 // @Description: The maximum ascending vertical velocity the pilot may request in m/s
49 // @Units: m/s
50 // @Range: 0.5 5
51 // @Increment: 0.1
52 // @User: Standard
53 AP_GROUPINFO("PILOT_SPD_UP", 18, QuadPlane, pilot_speed_z_max_up, 2.50),
55 // @Param: PILOT_SPD_DN
56 // @DisplayName: Pilot maximum vertical speed down
57 // @Description: The maximum vertical velocity the pilot may request in m/s going down. If 0, uses Q_PILOT_SPD_UP value.
58 // @Units: m/s
59 // @Range: 0.5 5
60 // @Increment: 0.1
61 // @User: Standard
62 AP_GROUPINFO("PILOT_SPD_DN", 60, QuadPlane, pilot_speed_z_max_dn, 0),
64 // @Param: PILOT_ACCEL_Z
65 // @DisplayName: Pilot vertical acceleration
66 // @Description: The vertical acceleration used when pilot is controlling the altitude
67 // @Units: m/s/s
68 // @Range: 0.5 5
69 // @Increment: 0.1
70 // @User: Standard
71 AP_GROUPINFO("PILOT_ACCEL_Z", 19, QuadPlane, pilot_accel_z, 2.5),
73 // @Group: WP_
74 // @Path: ../libraries/AC_WPNav/AC_WPNav.cpp
75 AP_SUBGROUPPTR(wp_nav, "WP_", 20, QuadPlane, AC_WPNav),
77 // @Param: RC_SPEED
78 // @DisplayName: RC output speed in Hz
79 // @Description: This is the PWM refresh rate in Hz for QuadPlane quad motors
80 // @Units: Hz
81 // @Range: 50 500
82 // @Increment: 10
83 // @User: Standard
84 AP_GROUPINFO("RC_SPEED", 21, QuadPlane, rc_speed, 490),
86 // @Param: THR_MIN_PWM
87 // @DisplayName: Minimum PWM output
88 // @Description: This is the minimum PWM output for the quad motors
89 // @Units: PWM
90 // @Range: 800 2200
91 // @Increment: 1
92 // @User: Standard
93 // 22: THR_MIN_PWM
95 // @Param: THR_MAX_PWM
96 // @DisplayName: Maximum PWM output
97 // @Description: This is the maximum PWM output for the quad motors
98 // @Units: PWM
99 // @Range: 800 2200
100 // @Increment: 1
101 // @User: Standard
102 // 23: THR_MAX_PWM
104 // @Param: ASSIST_SPEED
105 // @DisplayName: Quadplane assistance speed
106 // @Description: This is the speed below which the quad motors will provide stability and lift assistance in fixed wing modes. The default value of 0 disables assistance but will generate a pre-arm failure to encourage users to set this parameter to -1, or a positive, non-zero value. If this is set to -1 then all Q_ASSIST features are disabled except during transitions. A high non-zero,positive value will lead to more false positives which can waste battery. A lower value will result in less false positive, but will result in assistance taking longer to trigger. If unsure then set to 3 m/s below the minimum airspeed you will fly at. If you don't have an airspeed sensor then use 5 m/s below the minimum airspeed you fly at.
107 // @Units: m/s
108 // @Range: 0 100
109 // @Increment: 0.1
110 // @User: Standard
111 AP_GROUPINFO("ASSIST_SPEED", 24, QuadPlane, assist.speed, 0),
113 // @Param: YAW_RATE_MAX
114 // @DisplayName: Maximum yaw rate
115 // @Description: This is the maximum yaw rate for pilot input on rudder stick in degrees/second
116 // @Units: deg/s
117 // @Range: 50 500
118 // @Increment: 1
119 // @User: Standard
121 // YAW_RATE_MAX index 25
123 // @Param: LAND_FINAL_SPD
124 // @DisplayName: Land final speed
125 // @Description: The descent speed for the final stage of landing in m/s
126 // @Units: m/s
127 // @Range: 0.3 2
128 // @Increment: 0.1
129 // @User: Standard
130 AP_GROUPINFO("LAND_FINAL_SPD", 26, QuadPlane, land_final_speed, 0.5),
132 // @Param: LAND_FINAL_ALT
133 // @DisplayName: Land final altitude
134 // @Description: The altitude at which we should switch to Q_LAND_SPEED descent rate
135 // @Units: m
136 // @Range: 0.5 50
137 // @Increment: 0.1
138 // @User: Standard
139 AP_GROUPINFO("LAND_FINAL_ALT", 27, QuadPlane, land_final_alt, 6),
141 // 28 was used by THR_MID
143 // @Param: TRAN_PIT_MAX
144 // @DisplayName: Transition max pitch
145 // @Description: Maximum pitch during transition to auto fixed wing flight
146 // @User: Standard
147 // @Range: 0 30
148 // @Units: deg
149 // @Increment: 1
150 AP_GROUPINFO("TRAN_PIT_MAX", 29, QuadPlane, transition_pitch_max, 3),
152 // frame class was moved from 30 when consolidating AP_Motors classes
153 #define FRAME_CLASS_OLD_IDX 30
154 // @Param: FRAME_CLASS
155 // @DisplayName: Frame Class
156 // @Description: Controls major frame class for multicopter component
157 // @Values: 0:Undefined, 1:Quad, 2:Hexa, 3:Octa, 4:OctaQuad, 5:Y6, 7:Tri, 10: Single/Dual, 12:DodecaHexa, 14:Deca, 15:Scripting Matrix, 17:Dynamic Scripting Matrix
158 // @User: Standard
159 AP_GROUPINFO("FRAME_CLASS", 46, QuadPlane, frame_class, 1),
161 // @Param: FRAME_TYPE
162 // @DisplayName: Frame Type (+, X or V)
163 // @Description: Controls motor mixing for multicopter component
164 // @Values: 0:Plus, 1:X, 2:V, 3:H, 4:V-Tail, 5:A-Tail, 10:Y6B, 11:Y6F, 12:BetaFlightX, 13:DJIX, 14:ClockwiseX, 15:I, 16:MOTOR_FRAME_TYPE_NYT_PLUS, 17:MOTOR_FRAME_TYPE_NYT_X, 18: BetaFlightXReversed, 19: Y4
165 // @User: Standard
166 AP_GROUPINFO("FRAME_TYPE", 31, QuadPlane, frame_type, 1),
168 // @Param: VFWD_GAIN
169 // @DisplayName: Forward velocity hold gain
170 // @Description: The use of this parameter is no longer recommended and has been superseded by a method that works in all VTOL modes with the exception of QAUTOTUNE which is controlled by the Q_FWD_THR_USE parameter. This Q_VFD_GAIN parameter controls use of the forward motor in VTOL modes that use the velocity controller. Set to 0 to disable this function. A value of 0.05 is a good place to start if you want to use the forward motor for position control. No forward motor will be used in QSTABILIZE or QHOVER modes. Use with QLOITER for position hold with the forward motor.
171 // @Range: 0 0.5
172 // @Increment: 0.01
173 // @User: Standard
174 AP_GROUPINFO("VFWD_GAIN", 32, QuadPlane, vel_forward.gain, 0),
176 // 33 was used by WVANE_GAIN
178 // 34 was used by WVANE_MINROLL
180 // @Param: RTL_ALT
181 // @DisplayName: QRTL return altitude
182 // @Description: The altitude which QRTL mode heads to initially
183 // @Units: m
184 // @Range: 1 200
185 // @Increment: 1
186 // @User: Standard
187 AP_GROUPINFO("RTL_ALT", 35, QuadPlane, qrtl_alt, 15),
189 // @Param: RTL_MODE
190 // @DisplayName: VTOL RTL mode
191 // @Description: If this is set to 1 then an RTL will change to QRTL when within RTL_RADIUS meters of the RTL destination, VTOL approach: vehicle will RTL at RTL alt and circle with a radius of Q_FW_LND_APR_RAD down to Q_RTL_ALT and then transition into the wind and QRTL, see 'AUTO VTOL Landing', QRTL Always: do a QRTL instead of RTL
192 // @Values: 0:Disabled,1:Enabled,2:VTOL approach,3:QRTL Always
193 // @User: Standard
194 AP_GROUPINFO("RTL_MODE", 36, QuadPlane, rtl_mode, 0),
196 // 37: TILT_MASK
197 // 38: TILT_RATE_UP
198 // 39: TILT_MAX
200 // @Param: GUIDED_MODE
201 // @DisplayName: Enable VTOL in GUIDED mode
202 // @Description: This enables use of VTOL in guided mode. When enabled the aircraft will switch to VTOL flight when the guided destination is reached and hover at the destination.
203 // @Values: 0:Disabled,1:Enabled
204 // @User: Standard
205 AP_GROUPINFO("GUIDED_MODE", 40, QuadPlane, guided_mode, 0),
207 // 41 was used by THR_MIN
209 // @Param: ESC_CAL
210 // @DisplayName: ESC Calibration
211 // @Description: This is used to calibrate the throttle range of the VTOL motors. Please read https://ardupilot.org/plane/docs/quadplane-esc-calibration.html before using. This parameter is automatically set back to 0 on every boot. This parameter only takes effect in QSTABILIZE mode. When set to 1 the output of all motors will come directly from the throttle stick when armed, and will be zero when disarmed. When set to 2 the output of all motors will be maximum when armed and zero when disarmed. Make sure you remove all properllers before using.
212 // @Values: 0:Disabled,1:ThrottleInput,2:FullInput
213 // @User: Standard
214 AP_GROUPINFO("ESC_CAL", 42, QuadPlane, esc_calibration, 0),
216 // @Param: VFWD_ALT
217 // @DisplayName: Forward velocity alt cutoff
218 // @Description: Controls altitude to disable forward velocity assist when below this relative altitude. This is useful to keep the forward velocity propeller from hitting the ground. Rangefinder height data is incorporated when available.
219 // @Units: m
220 // @Range: 0 10
221 // @Increment: 0.25
222 // @User: Standard
223 AP_GROUPINFO("VFWD_ALT", 43, QuadPlane, vel_forward_alt_cutoff, 0),
225 // @Param: LAND_ICE_CUT
226 // @DisplayName: Cut IC engine on landing
227 // @Description: This controls stopping an internal combustion engine in the final landing stage of a VTOL. This is important for aircraft where the forward thrust engine may experience prop-strike if left running during landing. This requires the engine controls are enabled using the ICE_* parameters.
228 // @Values: 0:Disabled,1:Enabled
229 // @User: Standard
230 AP_GROUPINFO("LAND_ICE_CUT", 44, QuadPlane, land_icengine_cut, 1),
232 // @Param: ASSIST_ANGLE
233 // @DisplayName: Quadplane assistance angle
234 // @Description: This is the angular error in attitude beyond which the quadplane VTOL motors will provide stability assistance. This will only be used if Q_ASSIST_SPEED is also positive and non-zero. Assistance will be given if the attitude is outside the normal attitude limits by at least 5 degrees and the angular error in roll or pitch is greater than this angle for at least Q_ASSIST_DELAY seconds. Set to zero to disable angle assistance.
235 // @Units: deg
236 // @Range: 0 90
237 // @Increment: 1
238 // @User: Standard
239 AP_GROUPINFO("ASSIST_ANGLE", 45, QuadPlane, assist.angle, 30),
241 // 47: TILT_TYPE
242 // 48: TAILSIT_ANGLE
243 // 61: TAILSIT_ANG_VT
244 // 49: TILT_RATE_DN
245 // 50: TAILSIT_INPUT
246 // 51: TAILSIT_MASK
247 // 52: TAILSIT_MASKCH
248 // 53: TAILSIT_VFGAIN
249 // 54: TAILSIT_VHGAIN
250 // 56: TAILSIT_VHPOW
252 // @Param: MAV_TYPE
253 // @DisplayName: MAVLink type identifier
254 // @Description: This controls the mavlink type given in HEARTBEAT messages. For some GCS types a particular setting will be needed for correct operation.
255 // @Values: 0:AUTO,1:FIXED_WING,2:QUADROTOR,3:COAXIAL,4:HELICOPTER,7:AIRSHIP,8:FREE_BALLOON,9:ROCKET,10:GROUND_ROVER,11:SURFACE_BOAT,12:SUBMARINE,16:FLAPPING_WING,17:KITE,19:VTOL_DUOROTOR,20:VTOL_QUADROTOR,21:VTOL_TILTROTOR
256 AP_GROUPINFO("MAV_TYPE", 57, QuadPlane, mav_type, 0),
258 // @Param: OPTIONS
259 // @DisplayName: quadplane options
260 // @Description: See description for each bitmask bit description
261 // @Bitmask: 0: Level Transition-keep wings within LEVEL_ROLL_LIMIT and only use forward motor(s) for climb during transition
262 // @Bitmask: 1: Allow FW Takeoff-if bit is not set then NAV_TAKEOFF command on quadplanes will instead perform a NAV_VTOL takeoff
263 // @Bitmask: 2: Allow FW Land-if bit is not set then NAV_LAND command on quadplanes will instead perform a NAV_VTOL_LAND
264 // @Bitmask: 3: Vtol Takeoff Frame-command NAV_VTOL_TAKEOFF alt set by the command's reference frame not above current location
265 // @Bitmask: 4: Always use FW spiral approach-always use Use a fixed wing spiral approach for VTOL landings
266 // @Bitmask: 5: USE QRTL-instead of QLAND for rc failsafe when in VTOL modes
267 // @Bitmask: 6: Use Governor-use ICE Idle Governor in MANUAL for forward motor
268 // @Bitmask: 7: Force Qassist-on always
269 // @Bitmask: 8: Mtrs_Only_Qassist-in tailsitters only uses VTOL motors and not flying surfaces for QASSIST
270 // @Bitmask: 10: Disarmed Yaw Tilt-enable motor tilt for yaw when disarmed
271 // @Bitmask: 11: Delay Spoolup-delay VTOL spoolup for 2 seconds after arming
272 // @Bitmask: 12: Disable speed based Qassist when using synthethic airspeed estimates
273 // @Bitmask: 13: Disable Ground Effect Compensation-on baro altitude reports
274 // @Bitmask: 14: Ignore forward flight angle limits-in Qmodes and use Q_ANGLE_MAX exclusively
275 // @Bitmask: 15: ThrLandControl-enable throttle stick control of landing rate
276 // @Bitmask: 16: DisableApproach-disable use of approach and airbrake stages in VTOL landing
277 // @Bitmask: 17: EnableLandResposition-enable pilot controlled repositioning in AUTO land.Descent will pause while repositioning
278 // @Bitmask: 18: ARMVTOL-arm only in VTOL or AUTO modes
279 // @Bitmask: 19: CompleteTransition-to fixed wing if Q_TRANS_FAIL timer times out instead of QLAND
280 // @Bitmask: 20: Force RTL mode-forces RTL mode on rc failsafe in VTOL modes overriding bit 5(USE_QRTL)
281 // @Bitmask: 21: Tilt rotor-tilt motors up when disarmed in FW modes (except manual) to prevent ground strikes.
282 // @Bitmask: 22: Scale FF by the ratio of VTOL/plane angle P gains in VTOL modes rather than reducing VTOL angle P based on airspeed.
283 AP_GROUPINFO("OPTIONS", 58, QuadPlane, options, 0),
285 AP_SUBGROUPEXTENSION("",59, QuadPlane, var_info2),
287 // 60 is used above for VELZ_MAX_DN
288 // 61 was used above for TAILSIT_ANG_VT
290 AP_GROUPEND
293 // second table of user settable parameters for quadplanes, this
294 // allows us to go beyond the 64 parameter limit
295 const AP_Param::GroupInfo QuadPlane::var_info2[] = {
296 // @Param: TRANS_DECEL
297 // @DisplayName: Transition deceleration
298 // @Description: This is deceleration rate that will be used in calculating the stopping distance when transitioning from fixed wing flight to multicopter flight.
299 // @Units: m/s/s
300 // @Increment: 0.1
301 // @Range: 0.2 5
302 // @User: Standard
303 AP_GROUPINFO("TRANS_DECEL", 1, QuadPlane, transition_decel, 2.0),
305 // @Group: LOIT_
306 // @Path: ../libraries/AC_WPNav/AC_Loiter.cpp
307 AP_SUBGROUPPTR(loiter_nav, "LOIT_", 2, QuadPlane, AC_Loiter),
309 // 3: TAILSIT_GSCMAX
311 // @Param: TRIM_PITCH
312 // @DisplayName: Quadplane AHRS trim pitch
313 // @Description: This sets the compensation for the pitch angle trim difference between calibrated AHRS level and vertical flight pitch. NOTE! this is relative to calibrated AHRS trim, not forward flight trim which includes PTCH_TRIM_DEG. For tailsitters, this is relative to a baseline of 90 degrees in AHRS.
314 // @Units: deg
315 // @Range: -10 +10
316 // @Increment: 0.1
317 // @User: Advanced
318 // @RebootRequired: True
319 AP_GROUPINFO("TRIM_PITCH", 4, QuadPlane, ahrs_trim_pitch, 0),
321 // 5: TAILSIT_RLL_MX
323 #if QAUTOTUNE_ENABLED
324 // @Group: AUTOTUNE_
325 // @Path: ../libraries/AC_AutoTune/AC_AutoTune_Multi.cpp
326 AP_SUBGROUPINFO(qautotune, "AUTOTUNE_", 6, QuadPlane, QAutoTune),
327 #endif
329 // @Param: FW_LND_APR_RAD
330 // @DisplayName: Quadplane fixed wing landing approach radius
331 // @Description: This provides the radius used, when using a fixed wing landing approach. If set to 0 then the WP_LOITER_RAD will be selected.
332 // @Units: m
333 // @Range: 0 200
334 // @Increment: 5
335 // @User: Advanced
336 AP_GROUPINFO("FW_LND_APR_RAD", 7, QuadPlane, fw_land_approach_radius, 0),
338 // @Param: TRANS_FAIL
339 // @DisplayName: Quadplane transition failure time
340 // @Description: Maximum time allowed for forward transitions, exceeding this time will cancel the transition and the aircraft will immediately change to the mode set by Q_TRANS_FAIL_ACT or finish the transition depending on Q_OPTIONS bit 19. 0 for no limit.
341 // @Units: s
342 // @Range: 0 20
343 // @Increment: 1
344 // @User: Advanced
345 AP_GROUPINFO("TRANS_FAIL", 8, QuadPlane, transition_failure.timeout, 0),
347 // 9: TAILSIT_MOTMX
349 // @Param: THROTTLE_EXPO
350 // @DisplayName: Throttle expo strength
351 // @Description: Amount of curvature in throttle curve: 0 is linear, 1 is cubic
352 // @Range: 0 1
353 // @Increment: .1
354 // @User: Advanced
355 AP_GROUPINFO("THROTTLE_EXPO", 10, QuadPlane, throttle_expo, 0.2),
357 // @Param: ACRO_RLL_RATE
358 // @DisplayName: QACRO mode roll rate
359 // @Description: The maximum roll rate at full stick deflection in QACRO mode
360 // @Units: deg/s
361 // @Range: 10 500
362 // @Increment: 1
363 // @User: Standard
364 AP_GROUPINFO("ACRO_RLL_RATE", 11, QuadPlane, acro_roll_rate, 360),
366 // @Param: ACRO_PIT_RATE
367 // @DisplayName: QACRO mode pitch rate
368 // @Description: The maximum pitch rate at full stick deflection in QACRO mode
369 // @Units: deg/s
370 // @Range: 10 500
371 // @Increment: 1
372 // @User: Standard
373 AP_GROUPINFO("ACRO_PIT_RATE", 12, QuadPlane, acro_pitch_rate, 180),
375 // @Param: ACRO_YAW_RATE
376 // @DisplayName: QACRO mode yaw rate
377 // @Description: The maximum yaw rate at full stick deflection in QACRO mode
378 // @Units: deg/s
379 // @Range: 10 500
380 // @Increment: 1
381 // @User: Standard
382 AP_GROUPINFO("ACRO_YAW_RATE", 13, QuadPlane, acro_yaw_rate, 90),
384 // @Param: TKOFF_FAIL_SCL
385 // @DisplayName: Takeoff time failure scalar
386 // @Description: Scalar for how long past the expected takeoff time a takeoff should be considered as failed and the vehicle will switch to QLAND. If set to 0 there is no limit on takeoff time.
387 // @Range: 1.1 5.0
388 // @Increment: 5.1
389 // @User: Advanced
390 AP_GROUPINFO("TKOFF_FAIL_SCL", 14, QuadPlane, takeoff_failure_scalar, 0),
392 // @Param: TKOFF_ARSP_LIM
393 // @DisplayName: Takeoff airspeed limit
394 // @Description: Airspeed limit during takeoff. If the airspeed exceeds this level the vehicle will switch to QLAND. This is useful for ensuring that you don't takeoff into excessively strong wind. If set to 0 there is no limit on airspeed during takeoff.
395 // @Units: m/s
396 // @Range: 0 20
397 // @Increment: 1
398 // @User: Advanced
399 AP_GROUPINFO("TKOFF_ARSP_LIM", 15, QuadPlane, maximum_takeoff_airspeed, 0),
401 // @Param: ASSIST_ALT
402 // @DisplayName: Quadplane assistance altitude
403 // @Description: This is the altitude below which quadplane assistance will be triggered. This acts the same way as Q_ASSIST_ANGLE and Q_ASSIST_SPEED, but triggers if the aircraft drops below the given altitude while the VTOL motors are not running. A value of zero disables this feature. The altitude is calculated as being above ground level. The height above ground is given from a Lidar used if available and RNGFND_LANDING=1. Otherwise it comes from terrain data if TERRAIN_FOLLOW=1 and comes from height above home otherwise.
404 // @Units: m
405 // @Range: 0 120
406 // @Increment: 1
407 // @User: Standard
408 AP_GROUPINFO("ASSIST_ALT", 16, QuadPlane, assist.alt, 0),
410 // 17: TAILSIT_GSCMSK
411 // 18: TAILSIT_GSCMIN
413 // @Param: ASSIST_DELAY
414 // @DisplayName: Quadplane assistance delay
415 // @Description: This is delay between the assistance thresholds being met and the assistance starting.
416 // @Units: s
417 // @Range: 0 2
418 // @Increment: 0.1
419 // @User: Standard
420 AP_GROUPINFO("ASSIST_DELAY", 19, QuadPlane, assist.delay, 0.5),
422 // @Param: FWD_MANTHR_MAX
423 // @DisplayName: VTOL manual forward throttle max percent
424 // @Description: Maximum value for manual forward throttle; used with RC option FWD_THR (209)
425 // @Range: 0 100
426 AP_GROUPINFO("FWD_MANTHR_MAX", 20, QuadPlane, fwd_thr_max, 0),
428 // 21: TAILSIT_DSKLD
429 // 22: TILT_FIX_ANGLE
430 // 23: TILT_FIX_GAIN
431 // 24: TAILSIT_RAT_FW
432 // 25: TAILSIT_RAT_VT
434 // @Group: TAILSIT_
435 // @Path: tailsitter.cpp
436 AP_SUBGROUPINFO(tailsitter, "TAILSIT_", 26, QuadPlane, Tailsitter),
438 // @Group: TILT_
439 // @Path: tiltrotor.cpp
440 AP_SUBGROUPINFO(tiltrotor, "TILT_", 27, QuadPlane, Tiltrotor),
442 // @Param: BACKTRANS_MS
443 // @DisplayName: SLT and Tiltrotor back transition pitch limit duration
444 // @Description: Pitch angle will increase from 0 to angle max over this duration when switching into VTOL flight in a postion control mode. 0 Disables.
445 // @Units: ms
446 // @Range: 0 10000
447 AP_GROUPINFO("BACKTRANS_MS", 28, QuadPlane, back_trans_pitch_limit_ms, 3000),
449 // @Param: TRANS_FAIL_ACT
450 // @DisplayName: Quadplane transition failure action
451 // @Description: This sets the mode that is changed to when Q_TRANS_FAIL time elapses, if set. See also Q_OPTIONS bit 19: CompleteTransition if Q_TRANS_FAIL
452 // @Values: -1:Warn only, 0:QLand, 1:QRTL
453 AP_GROUPINFO("TRANS_FAIL_ACT", 29, QuadPlane, transition_failure.action, 0),
455 // @Group: WVANE_
456 // @Path: ../libraries/AC_AttitudeControl/AC_WeatherVane.cpp
457 AP_SUBGROUPPTR(weathervane, "WVANE_", 30, QuadPlane, AC_WeatherVane),
459 // @Param: LAND_ALTCHG
460 // @DisplayName: Land detection altitude change threshold
461 // @Description: The maximum altitude change allowed during land detection. You can raise this value if you find that landing detection takes a long time to complete. It is the maximum change in altitude over a period of 4 seconds for landing to be detected
462 // @Units: m
463 // @Range: 0.1 0.6
464 // @Increment: 0.05
465 // @User: Standard
466 AP_GROUPINFO("LAND_ALTCHG", 31, QuadPlane, landing_detect.detect_alt_change, 0.2),
468 // @Param: NAVALT_MIN
469 // @DisplayName: Minimum navigation altitude
470 // @Description: This is the altitude in meters above which navigation begins in auto takeoff. Below this altitude the target roll and pitch will be zero. A value of zero disables the feature
471 // @Range: 0 5
472 // @User: Advanced
473 AP_GROUPINFO("NAVALT_MIN", 32, QuadPlane, takeoff_navalt_min, 0),
475 // @Param: PLT_Y_RATE
476 // @DisplayName: Pilot controlled yaw rate
477 // @Description: Pilot controlled yaw rate max. Used in all pilot controlled modes except QAcro
478 // @Units: deg/s
479 // @Range: 1 360
480 // @User: Standard
482 // @Param: PLT_Y_EXPO
483 // @DisplayName: Pilot controlled yaw expo
484 // @Description: Pilot controlled yaw expo to allow faster rotation when stick at edges
485 // @Values: 0:Disabled,0.1:Very Low,0.2:Low,0.3:Medium,0.4:High,0.5:Very High
486 // @Range: -0.5 1.0
487 // @User: Advanced
489 // @Param: PLT_Y_RATE_TC
490 // @DisplayName: Pilot yaw rate control input time constant
491 // @Description: Pilot yaw rate control input time constant. Low numbers lead to sharper response, higher numbers to softer response.
492 // @Units: s
493 // @Range: 0 1
494 // @Increment: 0.01
495 // @Values: 0.5:Very Soft, 0.2:Soft, 0.15:Medium, 0.1:Crisp, 0.05:Very Crisp
496 // @User: Standard
497 AP_SUBGROUPINFO(command_model_pilot, "PLT_Y_", 33, QuadPlane, AC_CommandModel),
499 // @Param: RTL_ALT_MIN
500 // @DisplayName: QRTL minimum altitude
501 // @Description: If VTOL motors are active QRTL mode will VTOL climb to at least this altitude before returning home. If outside 150% the larger of WP_LOITER_RAD and RTL_RADIUS the vehicle will VTOL climb to Q_RTL_ALT. This parameter has no effect if the vehicle is in forward flight. Should be between Q_LAND_FINAL_ALT and Q_RTL_ALT
502 // @Units: m
503 // @Range: 1 200
504 // @Increment: 1
505 // @User: Standard
506 AP_GROUPINFO("RTL_ALT_MIN", 34, QuadPlane, qrtl_alt_min, 10),
508 // @Param: FWD_THR_GAIN
509 // @DisplayName: Q mode fwd throttle gain
510 // @Description: This parameter sets the gain from forward accel/tilt to forward throttle in certain Q modes. The Q modes this feature operates in is controlled by the Q_FWD_THR_USE parameter. Vehicles using separate forward thrust motors, eg quadplanes, should set this parameter to (all up weight) / (maximum combined thrust of forward motors) with a value of 2 being typical. Vehicles that tilt lifting rotors to provide forward thrust should set this parameter to (all up weight) / (weight lifted by tilting rotors) which for most aircraft can be approximated as (total number of lifting rotors) / (number of lifting rotors that tilt). When using this method of forward throttle control, the forward tilt angle limit is controlled by the Q_FWD_PIT_LIM parameter.
511 // @Range: 0.0 5.0
512 // @Increment: 0.1
513 // @User: Standard
514 AP_GROUPINFO("FWD_THR_GAIN", 35, QuadPlane, q_fwd_thr_gain, 2.0f),
516 // @Param: FWD_PIT_LIM
517 // @DisplayName: Q mode forward pitch limit
518 // @Description: When forward throttle is being controlled by the Q_FWD_THR_GAIN parameter in Q modes, the vehicle forward (nose down) pitch rotation will be limited to the value specified by this parameter and the any additional forward acceleration required will be produced by use of the forward thrust motor(s) or tilting of moveable rotors. Larger values allow the vehicle to pitch more nose down. Set initially to the amount of nose down pitch required to remove wing lift.
519 // @Units: deg
520 // @Range: 0.0 5.0
521 // @Increment: 0.1
522 // @User: Standard
523 AP_GROUPINFO("FWD_PIT_LIM", 36, QuadPlane, q_fwd_pitch_lim, 3.0f),
525 // @Param: FWD_THR_USE
526 // @DisplayName: Q mode forward throttle use
527 // @Description: This parameter determines when the feature that uses forward throttle instead of forward tilt is used. The amount of forward throttle is controlled by the Q_FWD_THR_GAIN parameter. The maximum amount of forward pitch allowed is controlled by the Q_FWD_PIT_LIM parameter. Q_FWD_THR_USE = 0 disables the feature. Q_FWD_THR_USE = 1 enables the feature in all position controlled modes such as QLOITER, QLAND, QRTL and VTOL TAKEOFF. Q_FWD_THR_USE = 2 enables the feature in all Q modes except QAUTOTUNE and QACRO. When enabling the feature, the legacy method of controlling forward throttle use via velocity controller error should be disabled by setting Q_VFWD_GAIN to 0. Do not use this feature with tailsitters.
528 // @Values: 0:Off,1:On in all position controlled Q modes,2:On in all Q modes except QAUTOTUNE and QACRO
529 // @User: Standard
530 AP_GROUPINFO("FWD_THR_USE", 37, QuadPlane, q_fwd_thr_use, uint8_t(FwdThrUse::OFF)),
532 // @Param: BCK_PIT_LIM
533 // @DisplayName: Q mode rearward pitch limit
534 // @Description: This sets the maximum number of degrees of back or pitch up in Q modes when the airspeed is at AIRSPEED_MIN, and is used to prevent excessive sutructural loads when pitching up decelerate. If airspeed is above or below AIRSPEED_MIN, the pitch up/back will be adjusted according to the formula pitch_limit = Q_BCK_PIT_LIM * (AIRSPEED_MIN / IAS)^2. The backwards/up pitch limit controlled by this parameter is in addition to limiting applied by PTCH_LIM_MAX_DEG and Q_ANGLE_MAX. The BCK_PIT_LIM limit is only applied when Q_FWD_THR_USE is set to 1 or 2 and the vehicle is flying in a mode that uses forward throttle instead of forward tilt to generate forward speed. Set to a non positive value 0 to deactivate this limit.
535 // @Units: deg
536 // @Range: 0.0 15.0
537 // @Increment: 0.1
538 // @User: Standard
539 AP_GROUPINFO("BCK_PIT_LIM", 38, QuadPlane, q_bck_pitch_lim, 10.0f),
541 AP_GROUPEND
545 defaults for all quadplanes
547 static const struct AP_Param::defaults_table_struct defaults_table[] = {
548 { "Q_A_RAT_RLL_P", 0.25 },
549 { "Q_A_RAT_RLL_I", 0.25 },
550 { "Q_A_RAT_RLL_FLTD", 10.0 },
551 { "Q_A_RAT_RLL_SMAX", 50.0 },
552 { "Q_A_RAT_PIT_P", 0.25 },
553 { "Q_A_RAT_PIT_I", 0.25 },
554 { "Q_A_RAT_PIT_FLTD", 10.0 },
555 { "Q_A_RAT_PIT_SMAX", 50.0 },
556 { "Q_A_RAT_YAW_SMAX", 50.0 },
557 { "Q_A_RATE_R_MAX", 75.0 },
558 { "Q_A_RATE_P_MAX", 75.0 },
559 { "Q_A_RATE_Y_MAX", 75.0 },
560 { "Q_M_SPOOL_TIME", 0.25 },
561 { "Q_LOIT_ANG_MAX", 15.0 },
562 { "Q_LOIT_ACC_MAX", 250.0 },
563 { "Q_LOIT_BRK_ACCEL", 50.0 },
564 { "Q_LOIT_BRK_JERK", 250 },
565 { "Q_LOIT_SPEED", 500 },
566 { "Q_WP_SPEED", 500 },
567 { "Q_WP_ACCEL", 100 },
568 { "Q_P_JERK_XY", 2 },
569 // lower rotational accel limits
570 { "Q_A_ACCEL_R_MAX", 40000 },
571 { "Q_A_ACCEL_P_MAX", 40000 },
572 { "Q_A_ACCEL_Y_MAX", 10000 },
576 conversion table for quadplane parameters
578 const AP_Param::ConversionInfo q_conversion_table[] = {
579 { Parameters::k_param_quadplane, 4044, AP_PARAM_FLOAT, "Q_P_POSZ_P" }, // Q_PZ_P
580 { Parameters::k_param_quadplane, 4045, AP_PARAM_FLOAT, "Q_P_POSXY_P"}, // Q_PXY_P
581 { Parameters::k_param_quadplane, 4046, AP_PARAM_FLOAT, "Q_P_VELXY_P"}, // Q_VXY_P
582 { Parameters::k_param_quadplane, 78, AP_PARAM_FLOAT, "Q_P_VELXY_I"}, // Q_VXY_I
583 { Parameters::k_param_quadplane, 142, AP_PARAM_FLOAT, "Q_P_VELXY_IMAX"}, // Q_VXY_IMAX
584 { Parameters::k_param_quadplane, 206, AP_PARAM_FLOAT, "Q_P_VELXY_FLTE"}, // Q_VXY_FILT_HZ
585 { Parameters::k_param_quadplane, 4047, AP_PARAM_FLOAT, "Q_P_VELZ_P"}, // Q_VZ_P
586 { Parameters::k_param_quadplane, 4048, AP_PARAM_FLOAT, "Q_P_ACCZ_P"}, // Q_AZ_P
587 { Parameters::k_param_quadplane, 80, AP_PARAM_FLOAT, "Q_P_ACCZ_I"}, // Q_AZ_I
588 { Parameters::k_param_quadplane, 144, AP_PARAM_FLOAT, "Q_P_ACCZ_D"}, // Q_AZ_D
589 { Parameters::k_param_quadplane, 336, AP_PARAM_FLOAT, "Q_P_ACCZ_IMAX"}, // Q_AZ_IMAX
590 { Parameters::k_param_quadplane, 400, AP_PARAM_FLOAT, "Q_P_ACCZ_FLTD"}, // Q_AZ_FILT
591 { Parameters::k_param_quadplane, 464, AP_PARAM_FLOAT, "Q_P_ACCZ_FF"}, // Q_AZ_FF
592 { Parameters::k_param_quadplane, 276, AP_PARAM_FLOAT, "Q_LOIT_SPEED"}, // Q_WP_LOIT_SPEED
593 { Parameters::k_param_quadplane, 468, AP_PARAM_FLOAT, "Q_LOIT_BRK_JERK" },// Q_WP_LOIT_JERK
594 { Parameters::k_param_quadplane, 532, AP_PARAM_FLOAT, "Q_LOIT_ACC_MAX" }, // Q_WP_LOIT_MAXA
595 { Parameters::k_param_quadplane, 596, AP_PARAM_FLOAT, "Q_LOIT_BRK_ACCEL" },// Q_WP_LOIT_MINA
596 { Parameters::k_param_q_attitude_control, 385, AP_PARAM_FLOAT, "Q_A_RAT_RLL_FLTD" },// Q_A_RAT_RLL_FILT
597 { Parameters::k_param_q_attitude_control, 386, AP_PARAM_FLOAT, "Q_A_RAT_PIT_FLTD" },// Q_A_RAT_PIT_FILT
598 { Parameters::k_param_q_attitude_control, 387, AP_PARAM_FLOAT, "Q_A_RAT_YAW_FLTE" },// Q_A_RAT_YAW_FILT
599 { Parameters::k_param_q_attitude_control, 449, AP_PARAM_FLOAT, "Q_A_RAT_RLL_FF" }, // Q_A_RAT_RLL_FF
600 { Parameters::k_param_q_attitude_control, 450, AP_PARAM_FLOAT, "Q_A_RAT_PIT_FF" }, // Q_A_RAT_PIT_FF
601 { Parameters::k_param_q_attitude_control, 451, AP_PARAM_FLOAT, "Q_A_RAT_YAW_FF" }, // Q_A_RAT_YAW_FILT
603 // tailsitter params have moved but retain the same names
604 { Parameters::k_param_quadplane, 48, AP_PARAM_INT8, "Q_TAILSIT_ANGLE" },
605 { Parameters::k_param_quadplane, 61, AP_PARAM_INT8, "Q_TAILSIT_ANG_VT" },
606 { Parameters::k_param_quadplane, 50, AP_PARAM_INT8, "Q_TAILSIT_INPUT" },
607 { Parameters::k_param_quadplane, 53, AP_PARAM_FLOAT, "Q_TAILSIT_VFGAIN" },
608 { Parameters::k_param_quadplane, 54, AP_PARAM_FLOAT, "Q_TAILSIT_VHGAIN" },
609 { Parameters::k_param_quadplane, 56, AP_PARAM_FLOAT, "Q_TAILSIT_VHPOW" },
610 { Parameters::k_param_quadplane, 251, AP_PARAM_FLOAT, "Q_TAILSIT_GSCMAX" },
611 { Parameters::k_param_quadplane, 379, AP_PARAM_FLOAT, "Q_TAILSIT_RLL_MX" },
612 { Parameters::k_param_quadplane, 635, AP_PARAM_INT16, "Q_TAILSIT_MOTMX" },
613 { Parameters::k_param_quadplane, 1147, AP_PARAM_INT16, "Q_TAILSIT_GSCMSK" },
614 { Parameters::k_param_quadplane, 1211, AP_PARAM_FLOAT, "Q_TAILSIT_GSCMIN" },
615 { Parameters::k_param_quadplane, 1403, AP_PARAM_FLOAT, "Q_TAILSIT_DSKLD" },
616 { Parameters::k_param_quadplane, 1595, AP_PARAM_FLOAT, "Q_TAILSIT_RAT_FW" },
617 { Parameters::k_param_quadplane, 1659, AP_PARAM_FLOAT, "Q_TAILSIT_RAT_FW" },
619 // tiltrotor params have moved but retain the same names
620 { Parameters::k_param_quadplane, 37, AP_PARAM_INT16, "Q_TILT_MASK" },
621 { Parameters::k_param_quadplane, 38, AP_PARAM_INT16, "Q_TILT_RATE_UP" },
622 { Parameters::k_param_quadplane, 39, AP_PARAM_INT8, "Q_TILT_MAX" },
623 { Parameters::k_param_quadplane, 47, AP_PARAM_INT8, "Q_TILT_TYPE" },
624 { Parameters::k_param_quadplane, 49, AP_PARAM_INT16, "Q_TILT_RATE_DN" },
625 { Parameters::k_param_quadplane, 55, AP_PARAM_FLOAT, "Q_TILT_YAW_ANGLE" },
626 { Parameters::k_param_quadplane, 1467, AP_PARAM_FLOAT, "Q_TILT_FIX_ANGLE" },
627 { Parameters::k_param_quadplane, 1531, AP_PARAM_FLOAT, "Q_TILT_FIX_GAIN" },
629 // PARAMETER_CONVERSION - Added: Jan-2022
630 { Parameters::k_param_quadplane, 33, AP_PARAM_FLOAT, "Q_WVANE_GAIN" }, // Moved from quadplane to weathervane library
631 { Parameters::k_param_quadplane, 34, AP_PARAM_FLOAT, "Q_WVANE_ANG_MIN" }, // Q_WVANE_MINROLL moved from quadplane to weathervane library
633 // PARAMETER_CONVERSION - Added: July-2022
634 { Parameters::k_param_quadplane, 25, AP_PARAM_FLOAT, "Q_PLT_Y_RATE" }, // Moved from quadplane to command model library
637 // PARAMETER_CONVERSION - Added: Oct-2021
638 const AP_Param::ConversionInfo mot_pwm_conversion_table[] = {
639 { Parameters::k_param_quadplane, 22, AP_PARAM_INT16, "Q_M_PWM_MIN" },
640 { Parameters::k_param_quadplane, 23, AP_PARAM_INT16, "Q_M_PWM_MAX" },
643 QuadPlane::QuadPlane(AP_AHRS &_ahrs) :
644 ahrs(_ahrs)
646 AP_Param::setup_object_defaults(this, var_info);
647 AP_Param::setup_object_defaults(this, var_info2);
649 if (_singleton != nullptr) {
650 AP_HAL::panic("Can only be one Quadplane");
652 _singleton = this;
656 // setup default motors for the frame class
657 void QuadPlane::setup_default_channels(uint8_t num_motors)
659 for (uint8_t i=0; i<num_motors; i++) {
660 SRV_Channels::set_aux_channel_default(SRV_Channels::get_motor_function(i), CH_5+i);
665 bool QuadPlane::setup(void)
667 if (initialised) {
668 return true;
670 if (!enable || hal.util->get_soft_armed()) {
671 return false;
675 cope with upgrade from old AP_Motors values for frame_class
677 AP_Int8 old_class;
678 const AP_Param::ConversionInfo cinfo { Parameters::k_param_quadplane, FRAME_CLASS_OLD_IDX, AP_PARAM_INT8, nullptr };
679 if (AP_Param::find_old_parameter(&cinfo, &old_class) && !frame_class.load()) {
680 uint8_t new_value = 0;
681 // map from old values to new values
682 switch (old_class.get()) {
683 case 0:
684 new_value = AP_Motors::MOTOR_FRAME_QUAD;
685 break;
686 case 1:
687 new_value = AP_Motors::MOTOR_FRAME_HEXA;
688 break;
689 case 2:
690 new_value = AP_Motors::MOTOR_FRAME_OCTA;
691 break;
692 case 3:
693 new_value = AP_Motors::MOTOR_FRAME_OCTAQUAD;
694 break;
695 case 4:
696 new_value = AP_Motors::MOTOR_FRAME_Y6;
697 break;
699 frame_class.set_and_save(new_value);
702 if (hal.util->available_memory() <
703 4096 + sizeof(*motors) + sizeof(*attitude_control) + sizeof(*pos_control) + sizeof(*wp_nav) + sizeof(*ahrs_view) + sizeof(*loiter_nav) + sizeof(*weathervane)) {
704 AP_BoardConfig::config_error("Not enough memory for quadplane");
708 dynamically allocate the key objects for quadplane. This ensures
709 that the objects don't affect the vehicle unless enabled and
710 also saves memory when not in use
712 switch ((AP_Motors::motor_frame_class)frame_class) {
713 case AP_Motors::MOTOR_FRAME_QUAD:
714 setup_default_channels(4);
715 break;
716 case AP_Motors::MOTOR_FRAME_HEXA:
717 setup_default_channels(6);
718 break;
719 case AP_Motors::MOTOR_FRAME_OCTA:
720 case AP_Motors::MOTOR_FRAME_OCTAQUAD:
721 setup_default_channels(8);
722 break;
723 case AP_Motors::MOTOR_FRAME_Y6:
724 setup_default_channels(7);
725 break;
726 case AP_Motors::MOTOR_FRAME_TRI:
727 SRV_Channels::set_default_function(CH_5, SRV_Channel::k_motor1);
728 SRV_Channels::set_default_function(CH_6, SRV_Channel::k_motor2);
729 SRV_Channels::set_default_function(CH_8, SRV_Channel::k_motor4);
730 SRV_Channels::set_default_function(CH_11, SRV_Channel::k_motor7);
731 AP_Param::set_frame_type_flags(AP_PARAM_FRAME_TRICOPTER);
732 break;
733 case AP_Motors::MOTOR_FRAME_TAILSITTER:
734 case AP_Motors::MOTOR_FRAME_SCRIPTING_MATRIX:
735 case AP_Motors::MOTOR_FRAME_DYNAMIC_SCRIPTING_MATRIX:
736 break;
737 default:
738 AP_BoardConfig::config_error("Unsupported Q_FRAME_CLASS %u", (unsigned int)(frame_class.get()));
741 // Make sure not both a tailsiter and tiltrotor
742 if ((tailsitter.enable > 0) && (tiltrotor.enable > 0)) {
743 AP_BoardConfig::config_error("set TAILSIT_ENABLE 0 or TILT_ENABLE 0");
746 switch ((AP_Motors::motor_frame_class)frame_class) {
747 case AP_Motors::MOTOR_FRAME_TRI:
748 motors = NEW_NOTHROW AP_MotorsTri(rc_speed);
749 motors_var_info = AP_MotorsTri::var_info;
750 break;
751 case AP_Motors::MOTOR_FRAME_TAILSITTER:
752 // this is a duo-motor tailsitter
753 tailsitter.tailsitter_motors = NEW_NOTHROW AP_MotorsTailsitter(rc_speed);
754 motors = tailsitter.tailsitter_motors;
755 motors_var_info = AP_MotorsTailsitter::var_info;
756 break;
757 case AP_Motors::MOTOR_FRAME_DYNAMIC_SCRIPTING_MATRIX:
758 #if AP_SCRIPTING_ENABLED
759 motors = NEW_NOTHROW AP_MotorsMatrix_Scripting_Dynamic(plane.scheduler.get_loop_rate_hz());
760 motors_var_info = AP_MotorsMatrix_Scripting_Dynamic::var_info;
761 #endif // AP_SCRIPTING_ENABLED
762 break;
763 default:
764 motors = NEW_NOTHROW AP_MotorsMatrix(rc_speed);
765 motors_var_info = AP_MotorsMatrix::var_info;
766 break;
769 if (!motors) {
770 AP_BoardConfig::allocation_error("motors");
773 AP_Param::load_object_from_eeprom(motors, motors_var_info);
775 // create the attitude view used by the VTOL code
776 ahrs_view = ahrs.create_view((tailsitter.enable > 0) ? ROTATION_PITCH_90 : ROTATION_NONE, ahrs_trim_pitch);
777 if (ahrs_view == nullptr) {
778 AP_BoardConfig::allocation_error("ahrs_view");
781 attitude_control = NEW_NOTHROW AC_AttitudeControl_TS(*ahrs_view, aparm, *motors);
782 if (!attitude_control) {
783 AP_BoardConfig::allocation_error("attitude_control");
786 AP_Param::load_object_from_eeprom(attitude_control, attitude_control->var_info);
787 pos_control = NEW_NOTHROW AC_PosControl(*ahrs_view, inertial_nav, *motors, *attitude_control);
788 if (!pos_control) {
789 AP_BoardConfig::allocation_error("pos_control");
791 AP_Param::load_object_from_eeprom(pos_control, pos_control->var_info);
792 wp_nav = NEW_NOTHROW AC_WPNav(inertial_nav, *ahrs_view, *pos_control, *attitude_control);
793 if (!wp_nav) {
794 AP_BoardConfig::allocation_error("wp_nav");
796 AP_Param::load_object_from_eeprom(wp_nav, wp_nav->var_info);
798 loiter_nav = NEW_NOTHROW AC_Loiter(inertial_nav, *ahrs_view, *pos_control, *attitude_control);
799 if (!loiter_nav) {
800 AP_BoardConfig::allocation_error("loiter_nav");
802 AP_Param::load_object_from_eeprom(loiter_nav, loiter_nav->var_info);
804 weathervane = NEW_NOTHROW AC_WeatherVane();
805 if (!weathervane) {
806 AP_BoardConfig::allocation_error("weathervane");
808 AP_Param::load_object_from_eeprom(weathervane, weathervane->var_info);
810 motors->init(frame_class, frame_type);
811 motors->update_throttle_range();
812 motors->set_update_rate(rc_speed);
813 attitude_control->parameter_sanity_check();
815 // Try to convert mot PWM params, if still invalid force conversion
816 AP_Param::convert_old_parameters(&mot_pwm_conversion_table[0], ARRAY_SIZE(mot_pwm_conversion_table));
817 if (!motors->check_mot_pwm_params()) {
818 AP_Param::convert_old_parameters(&mot_pwm_conversion_table[0], ARRAY_SIZE(mot_pwm_conversion_table), AP_Param::CONVERT_FLAG_FORCE);
821 // setup the trim of any motors used by AP_Motors so I/O board
822 // failsafe will disable motors
823 uint32_t mask = plane.quadplane.motors->get_motor_mask();
824 hal.rcout->set_failsafe_pwm(mask, plane.quadplane.motors->get_pwm_output_min());
826 // default QAssist state as set with Q_OPTIONS
827 if (option_is_set(QuadPlane::OPTION::Q_ASSIST_FORCE_ENABLE)) {
828 assist.set_state(VTOL_Assist::STATE::FORCE_ENABLED);
831 setup_defaults();
833 AP_Param::convert_old_parameters(&q_conversion_table[0], ARRAY_SIZE(q_conversion_table));
835 // centi-conversions added January 2024
836 land_final_speed.convert_centi_parameter(AP_PARAM_INT16);
837 pilot_speed_z_max_up.convert_centi_parameter(AP_PARAM_INT16);
838 pilot_speed_z_max_dn.convert_centi_parameter(AP_PARAM_INT16);
839 pilot_accel_z.convert_centi_parameter(AP_PARAM_INT16);
841 tailsitter.setup();
843 tiltrotor.setup();
845 if (!transition) {
846 transition = NEW_NOTHROW SLT_Transition(*this, motors);
848 if (!transition) {
849 AP_BoardConfig::allocation_error("transition");
852 // init wp_nav variables after detaults are setup
853 wp_nav->wp_and_spline_init();
855 transition->force_transition_complete();
857 // param count will have changed
858 AP_Param::invalidate_count();
860 char frame_and_type_string[30];
861 motors->get_frame_and_type_string(frame_and_type_string, ARRAY_SIZE(frame_and_type_string));
862 gcs().send_text(MAV_SEVERITY_INFO, "QuadPlane initialised, %s", frame_and_type_string);
863 initialised = true;
864 return true;
868 setup default parameters from defaults_table
870 void QuadPlane::setup_defaults(void)
872 AP_Param::set_defaults_from_table(defaults_table, ARRAY_SIZE(defaults_table));
874 // reset ESC calibration
875 if (esc_calibration != 0) {
876 esc_calibration.set_and_save(0);
878 // Quadplanes need the same level of GPS error checking as Copters do, Plane is more relaxed
879 AP_Param::set_default_by_name("EK2_CHECK_SCALE",100);
880 AP_Param::set_default_by_name("EK3_CHECK_SCALE",100);
884 // run ESC calibration
885 void QuadPlane::run_esc_calibration(void)
887 if (!motors->armed()) {
888 motors->set_throttle_passthrough_for_esc_calibration(0);
889 AP_Notify::flags.esc_calibration = false;
890 return;
892 if (!AP_Notify::flags.esc_calibration) {
893 gcs().send_text(MAV_SEVERITY_INFO, "Starting ESC calibration");
895 AP_Notify::flags.esc_calibration = true;
896 switch (esc_calibration) {
897 case 1:
898 // throttle based calibration
899 motors->set_throttle_passthrough_for_esc_calibration(plane.get_throttle_input() * 0.01f);
900 break;
901 case 2:
902 // full range calibration
903 motors->set_throttle_passthrough_for_esc_calibration(1);
904 break;
909 ask the multicopter attitude control to match the roll and pitch rates being demanded by the
910 fixed wing controller if not in a pure VTOL mode
912 void QuadPlane::multicopter_attitude_rate_update(float yaw_rate_cds)
914 bool use_multicopter_control = in_vtol_mode() && !tailsitter.in_vtol_transition();
915 bool use_yaw_target = false;
917 float yaw_target_cd = 0.0;
918 if (!use_multicopter_control && transition->update_yaw_target(yaw_target_cd)) {
919 use_multicopter_control = true;
920 use_yaw_target = true;
923 // normal control modes for VTOL and FW flight
924 // tailsitter in transition to VTOL flight is not really in a VTOL mode yet
925 if (use_multicopter_control) {
927 // Pilot input, use yaw rate time constant
928 set_pilot_yaw_rate_time_constant();
930 // tailsitter-only body-frame roll control options
931 // Angle mode attitude control for pitch and body-frame roll, rate control for euler yaw.
932 if (tailsitter.enabled() &&
933 (tailsitter.input_type & Tailsitter::input::TAILSITTER_INPUT_BF_ROLL)) {
935 if (!(tailsitter.input_type & Tailsitter::input::TAILSITTER_INPUT_PLANE)) {
936 // In multicopter input mode, the roll and yaw stick axes are independent of pitch
937 attitude_control->input_euler_rate_yaw_euler_angle_pitch_bf_roll(false,
938 plane.nav_roll_cd,
939 plane.nav_pitch_cd,
940 yaw_rate_cds);
941 return;
942 } else {
943 // In plane input mode, the roll and yaw sticks are swapped
944 // and their effective axes rotate from yaw to roll and vice versa
945 // as pitch goes from zero to 90.
946 // So it is necessary to also rotate their scaling.
948 // Get the roll angle and yaw rate limits
949 int16_t roll_limit = aparm.angle_max;
950 // separate limit for tailsitter roll, if set
951 if (tailsitter.max_roll_angle > 0) {
952 roll_limit = tailsitter.max_roll_angle * 100.0f;
954 // Prevent a divide by zero
955 const float yaw_rate_max = command_model_pilot.get_rate();
956 float yaw_rate_limit = ((yaw_rate_max < 1.0f) ? 1 : yaw_rate_max) * 100.0f;
957 float yaw2roll_scale = roll_limit / yaw_rate_limit;
959 // Rotate as a function of Euler pitch and swap roll/yaw
960 float euler_pitch = radians(.01f * plane.nav_pitch_cd);
961 float spitch = fabsf(sinf(euler_pitch));
962 float y2r_scale = linear_interpolate(1, yaw2roll_scale, spitch, 0, 1);
964 float p_yaw_rate = plane.nav_roll_cd / y2r_scale;
965 float p_roll_angle = -y2r_scale * yaw_rate_cds;
967 attitude_control->input_euler_rate_yaw_euler_angle_pitch_bf_roll(true,
968 p_roll_angle,
969 plane.nav_pitch_cd,
970 p_yaw_rate);
971 return;
975 if (use_yaw_target) {
976 attitude_control->input_euler_angle_roll_pitch_yaw(plane.nav_roll_cd,
977 plane.nav_pitch_cd,
978 yaw_target_cd,
979 true);
980 } else {
981 // use euler angle attitude control
982 attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(plane.nav_roll_cd,
983 plane.nav_pitch_cd,
984 yaw_rate_cds);
986 } else {
987 // use the fixed wing desired rates
988 Vector3f bf_input_cd { plane.rollController.get_pid_info().target * 100.0f,
989 plane.pitchController.get_pid_info().target * 100.0f,
990 yaw_rate_cds };
992 // rotate into multicopter attitude refence frame
993 ahrs_view->rotate(bf_input_cd);
995 // disable yaw time constant for 1:1 match of desired rates
996 disable_yaw_rate_time_constant();
998 attitude_control->input_rate_bf_roll_pitch_yaw_2(bf_input_cd.x, bf_input_cd.y, bf_input_cd.z);
1002 // hold in stabilize with given throttle
1003 void QuadPlane::hold_stabilize(float throttle_in)
1005 // call attitude controller
1006 multicopter_attitude_rate_update(get_desired_yaw_rate_cds(false));
1008 if ((throttle_in <= 0) && !air_mode_active()) {
1009 set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
1010 attitude_control->set_throttle_out(0, true, 0);
1011 relax_attitude_control();
1012 } else {
1013 set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
1014 bool should_boost = true;
1015 if (tailsitter.enabled() && assisted_flight) {
1016 // tailsitters in forward flight should not use angle boost
1017 should_boost = false;
1019 attitude_control->set_throttle_out(throttle_in, should_boost, 0);
1023 // run the multicopter Z controller
1024 void QuadPlane::run_z_controller(void)
1026 if (motors->get_spool_state() != AP_Motors::SpoolState::THROTTLE_UNLIMITED ) {
1027 return;
1029 const uint32_t now = AP_HAL::millis();
1030 if (tailsitter.in_vtol_transition(now)) {
1031 // never run Z controller in tailsitter transtion
1032 return;
1034 if ((now - last_pidz_active_ms) > 20 || !pos_control->is_active_z()) {
1035 // set vertical speed and acceleration limits
1036 pos_control->set_max_speed_accel_z(-get_pilot_velocity_z_max_dn(), pilot_speed_z_max_up*100, pilot_accel_z*100);
1038 // initialise the vertical position controller
1039 if (!tailsitter.enabled()) {
1040 pos_control->init_z_controller();
1041 } else {
1042 // initialise the vertical position controller with no descent
1043 pos_control->init_z_controller_no_descent();
1045 last_pidz_init_ms = now;
1047 last_pidz_active_ms = now;
1048 pos_control->update_z_controller();
1051 void QuadPlane::relax_attitude_control()
1053 // disable roll and yaw control for vectored tailsitters
1054 // if not a vectored tailsitter completely disable attitude control
1055 attitude_control->relax_attitude_controllers(!tailsitter.relax_pitch());
1059 check for an EKF yaw reset
1061 void QuadPlane::check_yaw_reset(void)
1063 if (!initialised) {
1064 return;
1066 float yaw_angle_change_rad = 0.0f;
1067 uint32_t new_ekfYawReset_ms = ahrs.getLastYawResetAngle(yaw_angle_change_rad);
1068 if (new_ekfYawReset_ms != ekfYawReset_ms) {
1069 attitude_control->inertial_frame_reset();
1070 ekfYawReset_ms = new_ekfYawReset_ms;
1071 LOGGER_WRITE_EVENT(LogEvent::EKF_YAW_RESET);
1075 void QuadPlane::set_climb_rate_cms(float target_climb_rate_cms)
1077 pos_control->input_vel_accel_z(target_climb_rate_cms, 0, false);
1081 hold hover with target climb rate
1083 void QuadPlane::hold_hover(float target_climb_rate_cms)
1085 // motors use full range
1086 set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
1088 // set vertical speed and acceleration limits
1089 pos_control->set_max_speed_accel_z(-get_pilot_velocity_z_max_dn(), pilot_speed_z_max_up*100, pilot_accel_z*100);
1091 // call attitude controller
1092 multicopter_attitude_rate_update(get_desired_yaw_rate_cds(false));
1094 // call position controller
1095 set_climb_rate_cms(target_climb_rate_cms);
1097 run_z_controller();
1100 float QuadPlane::get_pilot_throttle()
1102 // get scaled throttle input
1103 float throttle_in = plane.channel_throttle->get_control_in();
1105 // normalize to [0,1]
1106 throttle_in /= plane.channel_throttle->get_range();
1108 if (is_positive(throttle_expo)) {
1109 // get hover throttle level [0,1]
1110 float thr_mid = motors->get_throttle_hover();
1111 float thrust_curve_expo = constrain_float(throttle_expo, 0.0f, 1.0f);
1113 // this puts mid stick at hover throttle
1114 return throttle_curve(thr_mid, thrust_curve_expo, throttle_in);
1115 } else {
1116 return throttle_in;
1121 get_pilot_desired_angle - transform pilot's roll or pitch input into a desired lean angle.
1122 The angle_max_cd and angle_limit_cd are mode dependent
1124 void QuadPlane::get_pilot_desired_lean_angles(float &roll_out_cd, float &pitch_out_cd, float angle_max_cd, float angle_limit_cd) const
1126 // failsafe check
1127 if (plane.failsafe.rc_failsafe || plane.failsafe.throttle_counter > 0) {
1128 roll_out_cd = 0;
1129 pitch_out_cd = 0;
1130 return;
1133 // fetch roll and pitch inputs
1134 roll_out_cd = plane.channel_roll->get_control_in();
1135 pitch_out_cd = plane.channel_pitch->get_control_in();
1137 // limit max lean angle, always allow for 10 degrees
1138 angle_limit_cd = constrain_float(angle_limit_cd, 1000.0f, angle_max_cd);
1140 // scale roll and pitch inputs to ANGLE_MAX parameter range
1141 float scaler = angle_max_cd/4500.0;
1142 roll_out_cd *= scaler;
1143 pitch_out_cd *= scaler;
1145 // apply circular limit
1146 float total_in = norm(pitch_out_cd, roll_out_cd);
1147 if (total_in > angle_limit_cd) {
1148 float ratio = angle_limit_cd / total_in;
1149 roll_out_cd *= ratio;
1150 pitch_out_cd *= ratio;
1153 // apply lateral tilt to euler roll conversion
1154 roll_out_cd = 100 * degrees(atanf(cosf(radians(pitch_out_cd*0.01))*tanf(radians(roll_out_cd*0.01))));
1158 get pilot throttle in for landing code. Return value on scale of 0 to 1
1160 float QuadPlane::get_pilot_land_throttle(void) const
1162 if (plane.rc_failsafe_active()) {
1163 // assume zero throttle if lost RC
1164 return 0;
1166 // get scaled throttle input
1167 float throttle_in = plane.channel_throttle->get_control_in();
1169 // normalize to [0,1]
1170 throttle_in /= plane.channel_throttle->get_range();
1172 return constrain_float(throttle_in, 0, 1);
1175 // helper for is_flying()
1176 bool QuadPlane::is_flying(void)
1178 if (!available()) {
1179 return false;
1181 if (plane.control_mode == &plane.mode_guided && guided_takeoff) {
1182 return true;
1184 if (motors->get_throttle() > 0.01f && !motors->limit.throttle_lower) {
1185 return true;
1187 if (tailsitter.in_vtol_transition()) {
1188 return true;
1190 return false;
1193 // crude landing detector to prevent tipover
1194 bool QuadPlane::should_relax(void)
1196 const uint32_t tnow = millis();
1198 bool motor_at_lower_limit = motors->limit.throttle_lower && attitude_control->is_throttle_mix_min();
1199 if (motors->get_throttle() < 0.01f) {
1200 motor_at_lower_limit = true;
1203 if (!motor_at_lower_limit) {
1204 landing_detect.lower_limit_start_ms = 0;
1205 landing_detect.land_start_ms = 0;
1206 return false;
1207 } else if (landing_detect.lower_limit_start_ms == 0) {
1208 landing_detect.lower_limit_start_ms = tnow;
1211 return (tnow - landing_detect.lower_limit_start_ms) > 1000;
1214 // see if we are flying in vtol
1215 bool QuadPlane::is_flying_vtol(void) const
1217 if (!available()) {
1218 return false;
1220 if (motors->get_spool_state() == AP_Motors::SpoolState::SHUT_DOWN) {
1221 // assume that with no motor outputs we're not flying in VTOL mode
1222 return false;
1224 if (motors->get_throttle() > 0.01f) {
1225 // if we are demanding more than 1% throttle then don't consider aircraft landed
1226 return true;
1228 if (plane.control_mode->is_vtol_man_throttle() && air_mode_active()) {
1229 // in manual throttle modes with airmode on, don't consider aircraft landed
1230 return true;
1232 if (plane.control_mode == &plane.mode_guided && guided_takeoff) {
1233 return true;
1235 if (plane.control_mode->is_vtol_man_mode()) {
1236 // in manual flight modes only consider aircraft landed when pilot demanded throttle is zero
1237 return is_positive(get_throttle_input());
1239 if (in_vtol_mode() && millis() - landing_detect.lower_limit_start_ms > 5000) {
1240 // use landing detector
1241 return true;
1243 return false;
1247 smooth out descent rate for landing to prevent a jerk as we get to
1248 land_final_alt.
1250 float QuadPlane::landing_descent_rate_cms(float height_above_ground)
1252 if (poscontrol.last_override_descent_ms != 0) {
1253 const uint32_t now = AP_HAL::millis();
1254 if (now - poscontrol.last_override_descent_ms < 1000) {
1255 return poscontrol.override_descent_rate*100;
1259 if (poscontrol.get_state() == QPOS_LAND_FINAL) {
1260 // when in final use descent rate for final even if alt has climbed again
1261 height_above_ground = MIN(height_above_ground, land_final_alt);
1263 const float max_climb_speed = wp_nav->get_default_speed_up();
1264 float ret = linear_interpolate(land_final_speed*100, wp_nav->get_default_speed_down(),
1265 height_above_ground,
1266 land_final_alt, land_final_alt+6);
1268 if (option_is_set(QuadPlane::OPTION::THR_LANDING_CONTROL)) {
1269 // allow throttle control for landing speed
1270 const float thr_in = get_pilot_land_throttle();
1271 if (thr_in > THR_CTRL_LAND_THRESH) {
1272 thr_ctrl_land = true;
1274 if (thr_ctrl_land) {
1275 const float dz = 0.1;
1276 const float thresh1 = 0.5+dz;
1277 const float thresh2 = 0.5-dz;
1278 const float scaling = 1.0 / (0.5 - dz);
1279 if (thr_in > thresh1) {
1280 // start climbing
1281 ret = -(thr_in - thresh1)*scaling*max_climb_speed;
1282 } else if (thr_in > thresh2) {
1283 // hold height
1284 ret = 0;
1285 } else {
1286 ret *= (thresh2 - thr_in)*scaling;
1291 if (poscontrol.pilot_correction_active) {
1292 // stop descent when repositioning
1293 ret = MIN(0, ret);
1296 return ret;
1300 get pilot input yaw rate in cd/s
1302 float QuadPlane::get_pilot_input_yaw_rate_cds(void) const
1304 const auto rudder_in = plane.channel_rudder->get_control_in();
1305 bool manual_air_mode = plane.control_mode->is_vtol_man_throttle() && air_mode_active();
1306 if (!manual_air_mode &&
1307 !is_positive(get_throttle_input()) &&
1308 (!plane.control_mode->does_auto_throttle() || motors->limit.throttle_lower) &&
1309 plane.arming.get_rudder_arming_type() == AP_Arming::RudderArming::ARMDISARM &&
1310 rudder_in < 0 &&
1311 fabsf(inertial_nav.get_velocity_z_up_cms()) < 0.5 * get_pilot_velocity_z_max_dn()) {
1312 // the user may be trying to disarm, disable pilot yaw control
1313 return 0;
1316 if ((plane.g.stick_mixing == StickMixing::NONE) &&
1317 (plane.control_mode == &plane.mode_qrtl ||
1318 plane.control_mode->is_guided_mode() ||
1319 in_vtol_auto())) {
1320 return 0;
1323 // add in rudder input
1324 const float yaw_rate_max = command_model_pilot.get_rate();
1325 float max_rate = yaw_rate_max;
1326 if (!in_vtol_mode() && tailsitter.enabled()) {
1327 // scale by RUDD_DT_GAIN when not in a VTOL mode for
1328 // tailsitters. This allows for flat turns in tailsitters for
1329 // fixed wing modes if you want them, but prevents crazy yaw
1330 // rate demands in fixed wing based on your preferred yaw rate
1331 // when hovering
1332 max_rate *= plane.g2.rudd_dt_gain * 0.01;
1334 if (tailsitter.enabled() &&
1335 tailsitter.input_type & Tailsitter::input::TAILSITTER_INPUT_BF_ROLL) {
1336 // must have a non-zero max yaw rate for scaling to work
1337 max_rate = (yaw_rate_max < 1.0f) ? 1 : yaw_rate_max;
1339 return input_expo(rudder_in * (1/4500.0), command_model_pilot.get_expo()) * max_rate * 100.0;
1343 get overall desired yaw rate in cd/s
1345 float QuadPlane::get_desired_yaw_rate_cds(bool should_weathervane)
1347 float yaw_cds = 0;
1348 if (assisted_flight) {
1349 // use bank angle to get desired yaw rate
1350 yaw_cds += desired_auto_yaw_rate_cds();
1353 // add in pilot input
1354 yaw_cds += get_pilot_input_yaw_rate_cds();
1356 if (should_weathervane) {
1357 // add in weathervaning
1358 yaw_cds += get_weathervane_yaw_rate_cds();
1361 return yaw_cds;
1364 // get pilot desired climb rate in cm/s
1365 float QuadPlane::get_pilot_desired_climb_rate_cms(void) const
1367 if (!rc().has_valid_input()) {
1368 // no valid input means no sensible pilot desired climb rate.
1369 // descend at 0.5m/s for now
1370 return -50;
1372 uint16_t dead_zone = plane.channel_throttle->get_dead_zone();
1373 uint16_t trim = (plane.channel_throttle->get_radio_max() + plane.channel_throttle->get_radio_min())/2;
1374 const float throttle_request = plane.channel_throttle->pwm_to_angle_dz_trim(dead_zone, trim) *0.01f;
1375 return throttle_request * (throttle_request > 0.0f ? pilot_speed_z_max_up*100 : get_pilot_velocity_z_max_dn());
1380 initialise throttle_wait based on throttle and is_flying()
1382 void QuadPlane::init_throttle_wait(void)
1384 if (get_throttle_input() >= 10 ||
1385 plane.is_flying()) {
1386 throttle_wait = false;
1387 } else {
1388 throttle_wait = true;
1392 // set motor arming
1393 void QuadPlane::set_armed(bool armed)
1395 if (!initialised) {
1396 return;
1398 motors->armed(armed);
1400 if (plane.control_mode == &plane.mode_guided) {
1401 guided_wait_takeoff = armed;
1404 // re-init throttle wait on arm and disarm, to prevent rudder
1405 // arming on 2nd flight causing yaw
1406 if (!air_mode_active()) {
1407 init_throttle_wait();
1413 estimate desired climb rate for assistance (in cm/s)
1415 float QuadPlane::assist_climb_rate_cms(void) const
1417 float climb_rate;
1418 if (plane.control_mode->does_auto_throttle()) {
1419 // use altitude_error_cm, spread over 10s interval
1420 climb_rate = plane.calc_altitude_error_cm() * 0.1f;
1421 } else {
1422 // otherwise estimate from pilot input
1423 climb_rate = plane.g.flybywire_climb_rate * (plane.nav_pitch_cd/(plane.aparm.pitch_limit_max*100));
1424 climb_rate *= plane.get_throttle_input();
1426 climb_rate = constrain_float(climb_rate, -wp_nav->get_default_speed_down(), wp_nav->get_default_speed_up());
1428 // bring in the demanded climb rate over 2 seconds
1429 const uint32_t ramp_up_time_ms = 2000;
1430 const uint32_t dt_since_start = last_pidz_active_ms - last_pidz_init_ms;
1431 if (dt_since_start < ramp_up_time_ms) {
1432 climb_rate = linear_interpolate(0, climb_rate, dt_since_start, 0, ramp_up_time_ms);
1435 return climb_rate;
1439 calculate desired yaw rate for assistance
1441 float QuadPlane::desired_auto_yaw_rate_cds(void) const
1443 float aspeed;
1444 if (!ahrs.airspeed_estimate(aspeed) || aspeed < plane.aparm.airspeed_min) {
1445 aspeed = plane.aparm.airspeed_min;
1447 if (aspeed < 1) {
1448 aspeed = 1;
1450 float yaw_rate = degrees(GRAVITY_MSS * tanf(radians(plane.nav_roll_cd*0.01f))/aspeed) * 100;
1451 return yaw_rate;
1455 update for transition from quadplane to fixed wing mode
1457 void SLT_Transition::update()
1459 const uint32_t now = millis();
1461 if (!plane.arming.is_armed_and_safety_off()) {
1462 // reset the failure timer if we are disarmed
1463 transition_start_ms = now;
1466 float aspeed;
1467 bool have_airspeed = quadplane.ahrs.airspeed_estimate(aspeed);
1470 see if we should provide some assistance
1472 if (quadplane.assist.should_assist(aspeed, have_airspeed)) {
1473 // the quad should provide some assistance to the plane
1474 quadplane.assisted_flight = true;
1475 // update transition state for vehicles using airspeed wait
1476 if (!in_forced_transition) {
1477 const bool show_message = transition_state != TRANSITION_AIRSPEED_WAIT || transition_start_ms == 0;
1478 if (show_message) {
1479 gcs().send_text(MAV_SEVERITY_INFO, "Transition started airspeed %.1f", (double)aspeed);
1481 transition_state = TRANSITION_AIRSPEED_WAIT;
1482 if (transition_start_ms == 0) {
1483 transition_start_ms = now;
1486 } else {
1487 quadplane.assisted_flight = false;
1491 // if rotors are fully forward then we are not transitioning,
1492 // unless we are waiting for airspeed to increase (in which case
1493 // the tilt will decrease rapidly)
1494 if (quadplane.tiltrotor.fully_fwd() && transition_state != TRANSITION_AIRSPEED_WAIT) {
1495 if (transition_state == TRANSITION_TIMER) {
1496 gcs().send_text(MAV_SEVERITY_INFO, "Transition FW done");
1498 transition_state = TRANSITION_DONE;
1499 transition_start_ms = 0;
1500 transition_low_airspeed_ms = 0;
1503 if (transition_state < TRANSITION_DONE) {
1504 // during transition we ask TECS to use a synthetic
1505 // airspeed. Otherwise the pitch limits will throw off the
1506 // throttle calculation which is driven by pitch
1507 plane.TECS_controller.use_synthetic_airspeed();
1510 switch (transition_state) {
1511 case TRANSITION_AIRSPEED_WAIT: {
1512 quadplane.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
1513 // we hold in hover until the required airspeed is reached
1514 if (transition_start_ms == 0) {
1515 gcs().send_text(MAV_SEVERITY_INFO, "Transition airspeed wait");
1516 transition_start_ms = now;
1519 // check if we have failed to transition while in TRANSITION_AIRSPEED_WAIT
1520 if (transition_start_ms != 0 &&
1521 (quadplane.transition_failure.timeout > 0) &&
1522 ((now - transition_start_ms) > ((uint32_t)quadplane.transition_failure.timeout * 1000))) {
1523 if (!quadplane.transition_failure.warned) {
1524 gcs().send_text(MAV_SEVERITY_CRITICAL, "Transition failed, exceeded time limit");
1525 quadplane.transition_failure.warned = true;
1527 // if option is set and ground speed> 1/2 AIRSPEED_MIN for non-tiltrotors, then complete transition, otherwise QLAND.
1528 // tiltrotors will immediately transition
1529 const bool tiltrotor_with_ground_speed = quadplane.tiltrotor.enabled() && (plane.ahrs.groundspeed() > plane.aparm.airspeed_min * 0.5);
1530 if (quadplane.option_is_set(QuadPlane::OPTION::TRANS_FAIL_TO_FW) && tiltrotor_with_ground_speed) {
1531 transition_state = TRANSITION_TIMER;
1532 in_forced_transition = true;
1533 } else {
1534 switch (QuadPlane::TRANS_FAIL::ACTION(quadplane.transition_failure.action)) {
1535 case QuadPlane::TRANS_FAIL::ACTION::QLAND:
1536 plane.set_mode(plane.mode_qland, ModeReason::VTOL_FAILED_TRANSITION);
1537 break;
1539 case QuadPlane::TRANS_FAIL::ACTION::QRTL:
1540 plane.set_mode(plane.mode_qrtl, ModeReason::VTOL_FAILED_TRANSITION);
1541 quadplane.poscontrol.set_state(QuadPlane::QPOS_POSITION1);
1542 break;
1544 default:
1545 break;
1548 } else {
1549 quadplane.transition_failure.warned = false;
1552 transition_low_airspeed_ms = now;
1553 if (have_airspeed && aspeed > plane.aparm.airspeed_min && !quadplane.assisted_flight) {
1554 transition_state = TRANSITION_TIMER;
1555 airspeed_reached_tilt = quadplane.tiltrotor.current_tilt;
1556 gcs().send_text(MAV_SEVERITY_INFO, "Transition airspeed reached %.1f", (double)aspeed);
1558 quadplane.assisted_flight = true;
1560 // do not allow a climb on the quad motors during transition a
1561 // climb would add load to the airframe, and prolongs the
1562 // transition. We don't limit the climb rate on tilt rotors as
1563 // otherwise the plane can end up in high-alpha flight with
1564 // low VTOL thrust and may not complete a transition
1565 float climb_rate_cms = quadplane.assist_climb_rate_cms();
1566 if (quadplane.option_is_set(QuadPlane::OPTION::LEVEL_TRANSITION) && !quadplane.tiltrotor.enabled()) {
1567 climb_rate_cms = MIN(climb_rate_cms, 0.0f);
1569 quadplane.hold_hover(climb_rate_cms);
1571 if (!quadplane.tiltrotor.is_vectored()) {
1572 // set desired yaw to current yaw in both desired angle
1573 // and rate request. This reduces wing twist in transition
1574 // due to multicopter yaw demands. This is disabled when
1575 // using vectored yaw for tilt-rotors as the yaw control
1576 // is needed to maintain good control in forward
1577 // transitions
1578 quadplane.attitude_control->reset_yaw_target_and_rate();
1579 quadplane.attitude_control->rate_bf_yaw_target(0.0);
1581 if (quadplane.tiltrotor.enabled() && !quadplane.tiltrotor.has_fw_motor()) {
1582 // tilt rotors without decidated fw motors do not have forward throttle output in this stage
1583 // prevent throttle I wind up
1584 plane.TECS_controller.reset_throttle_I();
1587 last_throttle = motors->get_throttle();
1589 // reset integrators while we are below target airspeed as we
1590 // may build up too much while still primarily under
1591 // multicopter control
1592 plane.pitchController.reset_I();
1593 plane.rollController.reset_I();
1595 // give full authority to attitude control
1596 quadplane.attitude_control->set_throttle_mix_max(1.0f);
1597 break;
1600 case TRANSITION_TIMER: {
1601 quadplane.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
1602 // after airspeed is reached we degrade throttle over the
1603 // transition time, but continue to stabilize
1604 const uint32_t transition_timer_ms = now - transition_low_airspeed_ms;
1605 const float trans_time_ms = constrain_float(quadplane.transition_time_ms,500,30000);
1606 if (transition_timer_ms > unsigned(trans_time_ms)) {
1607 transition_state = TRANSITION_DONE;
1608 in_forced_transition = false;
1609 transition_start_ms = 0;
1610 transition_low_airspeed_ms = 0;
1611 gcs().send_text(MAV_SEVERITY_INFO, "Transition done");
1614 float transition_scale = (trans_time_ms - transition_timer_ms) / trans_time_ms;
1615 float throttle_scaled = last_throttle * transition_scale;
1617 // set zero throttle mix, to give full authority to
1618 // throttle. This ensures that the fixed wing controllers get
1619 // a chance to learn the right integrators during the transition
1620 quadplane.attitude_control->set_throttle_mix_value(0.5*transition_scale);
1622 if (throttle_scaled < 0.01) {
1623 // ensure we don't drop all the way to zero or the motors
1624 // will stop stabilizing
1625 throttle_scaled = 0.01;
1627 if (quadplane.tiltrotor.enabled() && !quadplane.tiltrotor.has_vtol_motor() && !quadplane.tiltrotor.has_fw_motor()) {
1628 // All motors tilting, Use a combination of vertical and forward throttle based on curent tilt angle
1629 // scale from all VTOL throttle at airspeed_reached_tilt to all forward throttle at fully forward tilt
1630 // this removes a step change in throttle once assistance is stoped
1631 const float ratio = (constrain_float(quadplane.tiltrotor.current_tilt, airspeed_reached_tilt, quadplane.tiltrotor.get_fully_forward_tilt()) - airspeed_reached_tilt) / (quadplane.tiltrotor.get_fully_forward_tilt() - airspeed_reached_tilt);
1632 const float fw_throttle = MAX(SRV_Channels::get_output_scaled(SRV_Channel::k_throttle),0) * 0.01;
1633 throttle_scaled = constrain_float(throttle_scaled * (1.0-ratio) + fw_throttle * ratio, 0.0, 1.0);
1635 quadplane.assisted_flight = true;
1636 quadplane.hold_stabilize(throttle_scaled);
1638 // set desired yaw to current yaw in both desired angle and
1639 // rate request while waiting for transition to
1640 // complete. Navigation should be controlled by fixed wing
1641 // control surfaces at this stage.
1642 // We disable this for vectored yaw tilt rotors as they do need active
1643 // yaw control throughout the transition
1644 if (!quadplane.tiltrotor.is_vectored()) {
1645 quadplane.attitude_control->reset_yaw_target_and_rate();
1646 quadplane.attitude_control->rate_bf_yaw_target(0.0);
1648 break;
1651 case TRANSITION_DONE:
1652 quadplane.set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN);
1653 motors->output();
1654 set_last_fw_pitch();
1655 in_forced_transition = false;
1656 return;
1659 quadplane.motors_output();
1661 set_last_fw_pitch();
1664 void SLT_Transition::VTOL_update()
1667 setup the transition state appropriately for next time we go into a non-VTOL mode
1669 transition_start_ms = 0;
1670 transition_low_airspeed_ms = 0;
1671 if (quadplane.throttle_wait && !plane.is_flying()) {
1672 in_forced_transition = false;
1673 transition_state = TRANSITION_DONE;
1674 } else {
1676 setup for airspeed wait for later
1678 transition_state = TRANSITION_AIRSPEED_WAIT;
1680 last_throttle = motors->get_throttle();
1682 // Keep assistance reset while not checking
1683 quadplane.assist.reset();
1687 update motor output for quadplane
1689 void QuadPlane::update(void)
1691 if (!setup()) {
1692 return;
1695 // keep motors interlock state upto date with E-stop
1696 motors->set_interlock(!SRV_Channels::get_emergency_stop());
1698 if ((ahrs_view != NULL) && !is_equal(_last_ahrs_trim_pitch, ahrs_trim_pitch.get())) {
1699 _last_ahrs_trim_pitch = ahrs_trim_pitch.get();
1700 ahrs_view->set_pitch_trim(_last_ahrs_trim_pitch);
1703 #if AP_ADVANCEDFAILSAFE_ENABLED
1704 if (plane.afs.should_crash_vehicle() && !plane.afs.terminating_vehicle_via_landing()) {
1705 set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN);
1706 motors->output();
1707 return;
1709 #endif
1711 if (motor_test.running) {
1712 motor_test_output();
1713 return;
1716 if (SRV_Channels::get_emergency_stop()) {
1717 attitude_control->reset_rate_controller_I_terms();
1720 if (!plane.arming.is_armed_and_safety_off()) {
1722 make sure we don't have any residual control from previous flight stages
1724 if (tailsitter.enabled()) {
1725 // tailsitters only relax I terms, to make ground testing easier
1726 attitude_control->reset_rate_controller_I_terms();
1727 } else {
1728 // otherwise full relax
1729 attitude_control->relax_attitude_controllers();
1731 // todo: do you want to set the throttle at this point?
1732 pos_control->relax_z_controller(0);
1735 const uint32_t now = AP_HAL::millis();
1736 if (!in_vtol_mode() && !in_vtol_airbrake()) {
1737 // we're in a fixed wing mode, cope with transitions and check
1738 // for assistance needed
1739 if (plane.control_mode == &plane.mode_manual ||
1740 plane.control_mode == &plane.mode_acro ||
1741 plane.control_mode == &plane.mode_training) {
1742 // in manual modes quad motors are always off
1743 if (!tailsitter.enabled()) {
1744 set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN);
1745 motors->output();
1747 transition->force_transition_complete();
1748 assisted_flight = false;
1749 } else {
1750 transition->update();
1753 } else {
1755 assisted_flight = in_vtol_airbrake();
1757 // output to motors
1758 motors_output();
1760 transition->VTOL_update();
1764 // disable throttle_wait when throttle rises above 10%
1765 if (throttle_wait &&
1766 (plane.get_throttle_input() > 10 ||
1767 !rc().has_valid_input())) {
1768 throttle_wait = false;
1771 tiltrotor.update();
1773 if (in_vtol_mode()) {
1774 // if enabled output forward throttle else 0
1775 float fwd_thr = 0;
1776 if (allow_forward_throttle_in_vtol_mode()) {
1777 fwd_thr = forward_throttle_pct();
1779 SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, fwd_thr);
1782 #if HAL_LOGGING_ENABLED
1783 // motors logging
1784 if (motors->armed()) {
1785 const bool motors_active = in_vtol_mode() || assisted_flight;
1786 if (motors_active && (motors->get_spool_state() != AP_Motors::SpoolState::SHUT_DOWN)) {
1787 // log RATE at main loop rate
1788 ahrs_view->Write_Rate(*motors, *attitude_control, *pos_control);
1790 // log CTRL and MOTB at 10 Hz
1791 if (now - last_ctrl_log_ms > 100) {
1792 last_ctrl_log_ms = now;
1793 attitude_control->control_monitor_log();
1794 motors->Log_Write();
1797 // log QTUN at 25 Hz if motors are active, or have been active in the last quarter second
1798 if ((motors_active || (now - last_motors_active_ms < 250)) && (now - last_qtun_log_ms > 40)) {
1799 last_qtun_log_ms = now;
1800 Log_Write_QControl_Tuning();
1803 #else
1804 (void)now;
1805 #endif // HAL_LOGGING_ENABLED
1809 see if motors should be shutdown. If they should be then change AP_Motors state to
1810 AP_Motors::DesiredSpoolState::SHUT_DOWN
1812 This is a safety check to prevent accidental motor runs on the
1813 ground, such as if RC fails and QRTL is started
1815 void QuadPlane::update_throttle_suppression(void)
1817 // if the motors have been running in the last 2 seconds then
1818 // allow them to run now
1819 if (AP_HAL::millis() - last_motors_active_ms < 2000) {
1820 return;
1823 // see if motors are already disabled
1824 if (motors->get_desired_spool_state() < AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED) {
1825 return;
1828 if (guided_wait_takeoff) {
1829 goto idle_state;
1832 /* if the users throttle is above zero then allow motors to run
1834 if the user has unset the "check throttle zero when arming"
1835 then the RC controller has a sprung throttle and we should not
1836 consider non-zero throttle to mean that pilot is commanding
1837 takeoff unless in a manual thottle mode
1839 if (!is_zero(get_throttle_input()) &&
1840 (rc().arming_check_throttle() ||
1841 plane.control_mode->is_vtol_man_throttle() ||
1842 plane.channel_throttle->norm_input_dz() > 0)) {
1843 return;
1846 // if in a VTOL manual throttle mode and air_mode is on then allow motors to run
1847 if (plane.control_mode->is_vtol_man_throttle() && air_mode_active()) {
1848 return;
1851 // if we are in a fixed wing auto throttle mode and we have
1852 // unsuppressed the throttle then allow motors to run
1853 if (plane.control_mode->does_auto_throttle() && !plane.throttle_suppressed) {
1854 return;
1857 // if our vertical velocity is greater than 1m/s then allow motors to run
1858 if (fabsf(inertial_nav.get_velocity_z_up_cms()) > 100) {
1859 return;
1862 // if we are more than 5m from home altitude then allow motors to run
1863 if (plane.relative_ground_altitude(plane.g.rangefinder_landing) > 5) {
1864 return;
1867 // allow for takeoff
1868 if (plane.control_mode == &plane.mode_auto && is_vtol_takeoff(plane.mission.get_current_nav_cmd().id)) {
1869 return;
1872 idle_state:
1873 // motors should be in the spin when armed state to warn user they could become active
1874 set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
1875 motors->set_throttle(0);
1876 last_motors_active_ms = 0;
1879 // update estimated throttle required to hover (if necessary)
1880 // called at 100hz
1881 void QuadPlane::update_throttle_hover()
1883 if (!available()) {
1884 return;
1887 // if not armed or landed exit
1888 if (!motors->armed() || !is_flying_vtol()) {
1889 return;
1892 // do not update while climbing or descending
1893 if (!is_zero(pos_control->get_vel_desired_cms().z)) {
1894 return;
1897 // do not update if quadplane forward motor is running (wing may be generating lift)
1898 // we use the THR_MIN value to account for petrol motors idling at THR_MIN
1899 if (!tailsitter.enabled() && (SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) > MAX(0,plane.aparm.throttle_min+10))) {
1900 return;
1903 // don't update if Z controller not running
1904 const uint32_t now = AP_HAL::millis();
1905 if (now - last_pidz_active_ms > 20) {
1906 return;
1909 // get throttle output
1910 float throttle = motors->get_throttle();
1912 float aspeed;
1913 // calc average throttle if we are in a level hover and low airspeed
1914 if (throttle > 0.0f && fabsf(inertial_nav.get_velocity_z_up_cms()) < 60 &&
1915 labs(ahrs_view->roll_sensor) < 500 && labs(ahrs_view->pitch_sensor) < 500 &&
1916 ahrs.airspeed_estimate(aspeed) && aspeed < plane.aparm.airspeed_min*0.3) {
1917 // Can we set the time constant automatically
1918 motors->update_throttle_hover(0.01f);
1919 #if HAL_GYROFFT_ENABLED
1920 plane.gyro_fft.update_freq_hover(0.01f, motors->get_throttle_out());
1921 #endif
1925 output motors and do any copter needed
1927 void QuadPlane::motors_output(bool run_rate_controller)
1929 /* Delay for ARMING_DELAY_MS after arming before allowing props to spin:
1930 1) for safety (OPTION_DELAY_ARMING)
1931 2) to allow motors to return to vertical (OPTION_DISARMED_TILT)
1933 if (option_is_set(QuadPlane::OPTION::DISARMED_TILT) || option_is_set(QuadPlane::OPTION::DELAY_ARMING)) {
1934 if (plane.arming.get_delay_arming()) {
1935 // delay motor start after arming
1936 set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN);
1937 motors->output();
1938 return;
1942 #if AP_ADVANCEDFAILSAFE_ENABLED
1943 if (!plane.arming.is_armed_and_safety_off() ||
1944 (plane.afs.should_crash_vehicle() && !plane.afs.terminating_vehicle_via_landing()) ||
1945 SRV_Channels::get_emergency_stop()) {
1946 #else
1947 if (!plane.arming.is_armed_and_safety_off() || SRV_Channels::get_emergency_stop()) {
1948 #endif
1949 set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN);
1950 motors->output();
1951 return;
1953 if (esc_calibration && AP_Notify::flags.esc_calibration && plane.control_mode == &plane.mode_qstabilize) {
1954 // output is direct from run_esc_calibration()
1955 return;
1958 const uint32_t now = AP_HAL::millis();
1959 if (tailsitter.in_vtol_transition(now) && !assisted_flight) {
1961 don't run the motor outputs while in tailsitter->vtol
1962 transition. That is taken care of by the fixed wing
1963 stabilisation code
1965 return;
1968 if (run_rate_controller) {
1969 if (now - last_att_control_ms > 100) {
1970 // relax if have been inactive
1971 relax_attitude_control();
1973 // run low level rate controllers that only require IMU data and set loop time
1974 const float last_loop_time_s = AP::scheduler().get_last_loop_time_s();
1975 motors->set_dt(last_loop_time_s);
1976 attitude_control->set_dt(last_loop_time_s);
1977 pos_control->set_dt(last_loop_time_s);
1978 attitude_control->rate_controller_run();
1979 last_att_control_ms = now;
1982 // see if motors should be shut down
1983 update_throttle_suppression();
1985 motors->output();
1987 // remember when motors were last active for throttle suppression
1988 if (motors->get_throttle() > 0.01f || tiltrotor.motors_active()) {
1989 last_motors_active_ms = now;
1995 handle a MAVLink DO_VTOL_TRANSITION
1997 bool QuadPlane::handle_do_vtol_transition(enum MAV_VTOL_STATE state) const
1999 if (!available()) {
2000 gcs().send_text(MAV_SEVERITY_NOTICE, "VTOL not available");
2001 return false;
2003 if (plane.control_mode != &plane.mode_auto) {
2004 gcs().send_text(MAV_SEVERITY_NOTICE, "VTOL transition only in AUTO");
2005 return false;
2007 switch (state) {
2008 case MAV_VTOL_STATE_MC:
2009 if (!plane.auto_state.vtol_mode) {
2010 gcs().send_text(MAV_SEVERITY_NOTICE, "Entered VTOL mode");
2012 plane.auto_state.vtol_mode = true;
2013 // This is a precaution. It should be looked after by the call to QuadPlane::mode_enter(void) on mode entry.
2014 plane.quadplane.q_fwd_throttle = 0.0f;
2015 plane.quadplane.q_fwd_pitch_lim_cd = 100.0f * plane.quadplane.q_fwd_pitch_lim;
2016 return true;
2018 case MAV_VTOL_STATE_FW:
2019 if (plane.auto_state.vtol_mode) {
2020 gcs().send_text(MAV_SEVERITY_NOTICE, "Exited VTOL mode");
2022 plane.auto_state.vtol_mode = false;
2024 return true;
2026 default:
2027 break;
2030 gcs().send_text(MAV_SEVERITY_NOTICE, "Invalid VTOL mode");
2031 return false;
2035 are we in a VTOL auto state?
2037 bool QuadPlane::in_vtol_auto(void) const
2039 if (!available()) {
2040 return false;
2042 if (plane.control_mode != &plane.mode_auto) {
2043 return false;
2045 if (plane.auto_state.vtol_mode) {
2046 return true;
2048 uint16_t id = plane.mission.get_current_nav_cmd().id;
2049 switch (id) {
2050 case MAV_CMD_NAV_VTOL_TAKEOFF:
2051 return true;
2052 case MAV_CMD_NAV_LOITER_UNLIM:
2053 case MAV_CMD_NAV_LOITER_TIME:
2054 case MAV_CMD_NAV_LOITER_TURNS:
2055 case MAV_CMD_NAV_LOITER_TO_ALT:
2056 return plane.auto_state.vtol_loiter;
2057 case MAV_CMD_NAV_TAKEOFF:
2058 return is_vtol_takeoff(id);
2059 case MAV_CMD_NAV_VTOL_LAND:
2060 case MAV_CMD_NAV_LAND:
2061 case MAV_CMD_NAV_PAYLOAD_PLACE:
2062 return is_vtol_land(id);
2063 default:
2064 return false;
2069 are we in a VTOL mode? This is used to decide if we run the
2070 transition handling code or not
2072 note that AIRBRAKE is not considered in_vtol_mode even though the
2073 VTOL motors are running
2075 bool QuadPlane::in_vtol_mode(void) const
2077 if (!available()) {
2078 return false;
2080 if (in_vtol_land_sequence()) {
2081 return poscontrol.get_state() != QPOS_APPROACH && poscontrol.get_state() != QPOS_AIRBRAKE;
2083 if (plane.control_mode->is_vtol_mode()) {
2084 return true;
2086 if (plane.control_mode->is_guided_mode()
2087 && plane.auto_state.vtol_loiter &&
2088 poscontrol.get_state() > QPOS_APPROACH) {
2089 return true;
2091 if (plane.control_mode == &plane.mode_guided &&
2092 guided_takeoff) {
2093 return true;
2095 if (in_vtol_auto()) {
2096 if (!plane.auto_state.vtol_loiter || poscontrol.get_state() > QPOS_AIRBRAKE) {
2097 return true;
2100 return false;
2104 are we in a VTOL mode that needs position and velocity estimates?
2106 bool QuadPlane::in_vtol_posvel_mode(void) const
2108 if (!available()) {
2109 return false;
2111 return (plane.control_mode == &plane.mode_qloiter ||
2112 plane.control_mode == &plane.mode_qland ||
2113 plane.control_mode == &plane.mode_qrtl ||
2114 #if QAUTOTUNE_ENABLED
2115 plane.control_mode == &plane.mode_qautotune ||
2116 #endif
2117 (plane.control_mode->is_guided_mode() &&
2118 plane.auto_state.vtol_loiter &&
2119 poscontrol.get_state() > QPOS_APPROACH) ||
2120 in_vtol_auto());
2124 update landing positioning offset
2126 void QuadPlane::update_land_positioning(void)
2128 if (!option_is_set(QuadPlane::OPTION::REPOSITION_LANDING)) {
2129 // not enabled
2130 poscontrol.pilot_correction_active = false;
2131 poscontrol.target_vel_cms.zero();
2132 return;
2134 const float scale = 1.0 / 4500;
2135 float roll_in = plane.channel_roll->get_control_in() * scale;
2136 float pitch_in = plane.channel_pitch->get_control_in() * scale;
2138 // limit correction speed to accel with stopping time constant of 0.5s
2139 const float speed_max_cms = wp_nav->get_wp_acceleration() * 0.5;
2140 const float dt = plane.scheduler.get_loop_period_s();
2142 poscontrol.target_vel_cms = Vector3f(-pitch_in, roll_in, 0) * speed_max_cms;
2143 poscontrol.target_vel_cms.rotate_xy(ahrs_view->yaw);
2145 // integrate our corrected position
2146 poscontrol.xy_correction += poscontrol.target_vel_cms.xy() * dt * 0.01;
2148 poscontrol.pilot_correction_active = (!is_zero(roll_in) || !is_zero(pitch_in));
2149 if (poscontrol.pilot_correction_active) {
2150 poscontrol.pilot_correction_done = true;
2155 run (and possibly init) xy controller
2157 void QuadPlane::run_xy_controller(float accel_limit)
2159 float accel_cmss = wp_nav->get_wp_acceleration();
2160 if (is_positive(accel_limit)) {
2161 // allow for accel limit override
2162 accel_cmss = MAX(accel_cmss, accel_limit*100);
2164 const float speed_cms = wp_nav->get_default_speed_xy();
2165 pos_control->set_max_speed_accel_xy(speed_cms, accel_cmss);
2166 pos_control->set_correction_speed_accel_xy(speed_cms, accel_cmss);
2167 if (!pos_control->is_active_xy()) {
2168 pos_control->init_xy_controller();
2170 pos_control->set_lean_angle_max_cd(MIN(4500, MAX(accel_to_angle(accel_limit)*100, aparm.angle_max)));
2171 if (q_fwd_throttle > 0.95f) {
2172 // prevent wind up of the velocity controller I term due to a saturated forward throttle
2173 pos_control->set_externally_limited_xy();
2175 pos_control->update_xy_controller();
2179 initialise QPOS_APPROACH
2181 void QuadPlane::poscontrol_init_approach(void)
2183 const float dist = plane.current_loc.get_distance(plane.next_WP_loc);
2184 if (option_is_set(QuadPlane::OPTION::DISABLE_APPROACH)) {
2185 // go straight to QPOS_POSITION1
2186 poscontrol.set_state(QPOS_POSITION1);
2187 gcs().send_text(MAV_SEVERITY_INFO,"VTOL Position1 d=%.1f", dist);
2188 } else if (poscontrol.get_state() != QPOS_APPROACH) {
2189 // check if we are close to the destination. We don't want to
2190 // do a full approach when very close
2191 if (dist < transition_threshold()) {
2192 if (tailsitter.enabled() || motors->get_desired_spool_state() == AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED) {
2193 gcs().send_text(MAV_SEVERITY_INFO,"VTOL Position1 d=%.1f", dist);
2194 poscontrol.set_state(QPOS_POSITION1);
2195 transition->set_last_fw_pitch();
2196 } else {
2197 gcs().send_text(MAV_SEVERITY_INFO,"VTOL airbrake v=%.1f d=%.0f sd=%.0f h=%.1f",
2198 plane.ahrs.groundspeed(),
2199 dist,
2200 stopping_distance(),
2201 plane.relative_ground_altitude(plane.g.rangefinder_landing));
2202 poscontrol.set_state(QPOS_AIRBRAKE);
2204 } else {
2205 gcs().send_text(MAV_SEVERITY_INFO,"VTOL approach d=%.1f", dist);
2206 poscontrol.set_state(QPOS_APPROACH);
2208 poscontrol.thrust_loss_start_ms = 0;
2210 poscontrol.pilot_correction_done = false;
2211 poscontrol.xy_correction.zero();
2212 poscontrol.slow_descent = false;
2215 #if HAL_LOGGING_ENABLED
2217 log the QPOS message
2219 void QuadPlane::log_QPOS(void)
2221 // @LoggerMessage: QPOS
2222 // @Description: Quadplane position data
2223 // @Field: TimeUS: Time since system startup
2224 // @Field: State: Position control state
2225 // @FieldValueEnum: State: QuadPlane::position_control_state
2226 // @Field: Dist: Distance to next waypoint
2227 // @Field: TSpd: Target speed
2228 // @Field: TAcc: Target acceleration
2229 // @Field: OShoot: True if landing point is overshot or heading off by more than 60 degrees
2231 AP::logger().WriteStreaming("QPOS", "TimeUS,State,Dist,TSpd,TAcc,OShoot", "QBfffB",
2232 AP_HAL::micros64(),
2233 poscontrol.get_state(),
2234 plane.auto_state.wp_distance,
2235 poscontrol.target_speed,
2236 poscontrol.target_accel,
2237 poscontrol.overshoot);
2239 #endif
2242 change position control state
2244 void QuadPlane::PosControlState::set_state(enum position_control_state s)
2246 const uint32_t now = AP_HAL::millis();
2247 if (state != s) {
2248 auto &qp = plane.quadplane;
2249 pilot_correction_done = false;
2250 // handle resets needed for when the state changes
2251 if (s == QPOS_POSITION1) {
2252 reached_wp_speed = false;
2253 // never do a rate reset, if attitude control is not active it will be automaticaly reset before running, see: last_att_control_ms
2254 // if it is active then the rate control should not be reset at all
2255 qp.attitude_control->reset_yaw_target_and_rate(false);
2256 pos1_speed_limit = plane.ahrs.groundspeed_vector().length();
2257 done_accel_init = false;
2258 } else if (s == QPOS_AIRBRAKE) {
2259 // start with zero integrator on vertical throttle
2260 qp.pos_control->get_accel_z_pid().set_integrator(0);
2261 } else if (s == QPOS_LAND_DESCEND) {
2262 // reset throttle descent control
2263 qp.thr_ctrl_land = false;
2264 qp.land_descend_start_alt = plane.current_loc.alt*0.01;
2265 last_override_descent_ms = 0;
2266 } else if (s == QPOS_LAND_ABORT) {
2267 // reset throttle descent control
2268 qp.thr_ctrl_land = false;
2269 } else if (s == QPOS_LAND_FINAL) {
2270 // remember last pos reset to handle GPS glitch in LAND_FINAL
2271 Vector2f rpos;
2272 last_pos_reset_ms = plane.ahrs.getLastPosNorthEastReset(rpos);
2273 qp.landing_detect.land_start_ms = 0;
2274 qp.landing_detect.lower_limit_start_ms = 0;
2276 // double log to capture the state change
2277 #if HAL_LOGGING_ENABLED
2278 qp.log_QPOS();
2279 #endif
2280 state = s;
2281 #if HAL_LOGGING_ENABLED
2282 qp.log_QPOS();
2283 #endif
2284 last_log_ms = now;
2285 overshoot = false;
2287 last_state_change_ms = now;
2289 // we consider setting the state to be equivalent to running to
2290 // prevent code from overriding the state as stale
2291 last_run_ms = now;
2295 main landing controller. Used for landing and RTL.
2297 void QuadPlane::vtol_position_controller(void)
2299 if (!setup()) {
2300 return;
2303 const Location &loc = plane.next_WP_loc;
2304 uint32_t now_ms = AP_HAL::millis();
2306 // distance that we switch to QPOS_POSITION2
2307 const float position2_dist_threshold = 10.0;
2309 // target speed when we reach position2 threshold
2310 const float position2_target_speed = 3.0;
2312 if (plane.arming.is_armed_and_safety_off()) {
2313 poscontrol.last_run_ms = now_ms;
2316 // avoid running the z controller in approach and airbrake if we're not already running it
2317 // and tilt is more than tilt max
2318 bool suppress_z_controller = false;
2320 Vector2f landing_velocity;
2321 if (now_ms - poscontrol.last_velocity_match_ms < 1000) {
2322 landing_velocity = poscontrol.velocity_match;
2325 // horizontal position control
2326 switch (poscontrol.get_state()) {
2328 case QPOS_NONE:
2329 poscontrol.set_state(QPOS_POSITION1);
2330 INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
2331 break;
2333 case QPOS_APPROACH:
2334 if (in_vtol_mode()) {
2335 // this means we're not running transition update code and
2336 // thus not doing qassist checking, force POSITION1 mode
2337 // now. We don't expect this to trigger, it is a failsafe
2338 // for a logic error
2339 gcs().send_text(MAV_SEVERITY_INFO,"VTOL position1 nvtol");
2340 poscontrol.set_state(QPOS_POSITION1);
2341 INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
2343 FALLTHROUGH;
2345 case QPOS_AIRBRAKE: {
2346 float aspeed;
2347 const Vector2f closing_vel = landing_closing_velocity();
2348 const Vector2f desired_closing_vel = landing_desired_closing_velocity();
2349 const float groundspeed = plane.ahrs.groundspeed();
2350 const float distance = plane.auto_state.wp_distance;
2351 const float closing_speed = closing_vel.length();
2352 const float desired_closing_speed = desired_closing_vel.length();
2353 if (!plane.ahrs.airspeed_estimate(aspeed)) {
2354 aspeed = groundspeed;
2357 if (tiltrotor.enabled() && poscontrol.get_state() == QPOS_AIRBRAKE) {
2358 if ((now_ms - last_pidz_active_ms > 2000 && tiltrotor.tilt_over_max_angle()) ||
2359 tiltrotor.current_tilt >= tiltrotor.get_fully_forward_tilt()) {
2360 // use low throttle stabilization when airbraking on a
2361 // tiltrotor. We don't want quite zero throttle as we
2362 // want some drag, but don't want to run the Z
2363 // controller which can result in high throttle on
2364 // motors that are tilted forward, thus increasing
2365 // speed
2366 suppress_z_controller = true;
2367 hold_stabilize(0.01);
2371 // speed for crossover to POSITION1 controller
2372 const float aspeed_threshold = MAX(plane.aparm.airspeed_min-2, assist.speed);
2374 // run fixed wing navigation
2375 plane.nav_controller->update_waypoint(plane.auto_state.crosstrack ? plane.prev_WP_loc : plane.current_loc, loc);
2377 // use TECS for throttle
2378 SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, plane.TECS_controller.get_throttle_demand());
2380 // use TECS for pitch
2381 int32_t commanded_pitch = plane.TECS_controller.get_pitch_demand();
2382 plane.nav_pitch_cd = constrain_int32(commanded_pitch, plane.pitch_limit_min*100, plane.aparm.pitch_limit_max.get()*100);
2383 if (poscontrol.get_state() == QPOS_AIRBRAKE) {
2384 // don't allow down pitch in airbrake
2385 plane.nav_pitch_cd = MAX(plane.nav_pitch_cd, 0);
2388 // use nav controller roll
2389 plane.calc_nav_roll();
2391 // work out the point to enter airbrake mode. We want enough
2392 // distance to stop, plus some margin for the time it takes to
2393 // change the accel (jerk limit) plus the min time in airbrake
2394 // mode. For simplicity we assume 2 seconds margin
2395 const float stop_distance = stopping_distance() + 2*closing_speed;
2397 if (!suppress_z_controller && poscontrol.get_state() == QPOS_AIRBRAKE) {
2398 hold_hover(0);
2399 // don't run Z controller again in this loop
2400 suppress_z_controller = true;
2404 see if we should start airbraking stage. For non-tailsitters
2405 we can use the VTOL motors as airbrakes by firing them up
2406 before we transition. This gives a smoother transition and
2407 gives us a nice lot of deceleration
2409 if (poscontrol.get_state() == QPOS_APPROACH && distance < stop_distance) {
2410 if (tailsitter.enabled() || motors->get_desired_spool_state() == AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED) {
2411 // tailsitters don't use airbrake stage for landing
2412 gcs().send_text(MAV_SEVERITY_INFO,"VTOL position1 v=%.1f d=%.0f sd=%.0f h=%.1f",
2413 groundspeed,
2414 plane.auto_state.wp_distance,
2415 stop_distance,
2416 plane.relative_ground_altitude(plane.g.rangefinder_landing));
2417 poscontrol.set_state(QPOS_POSITION1);
2418 transition->set_last_fw_pitch();
2419 } else {
2420 gcs().send_text(MAV_SEVERITY_INFO,"VTOL airbrake v=%.1f d=%.0f sd=%.0f h=%.1f",
2421 groundspeed,
2422 distance,
2423 stop_distance,
2424 plane.relative_ground_altitude(plane.g.rangefinder_landing));
2425 poscontrol.set_state(QPOS_AIRBRAKE);
2430 we must switch to POSITION1 if our airspeed drops below the
2431 assist speed. We additionally switch to POSITION1 if we are
2432 too far above our desired velocity profile, or our attitude
2433 has deviated too much
2435 const int32_t attitude_error_threshold_cd = 1000;
2437 // use at least 1s of airbrake time to ensure motors have a chance to
2438 // properly spin up
2439 const uint32_t min_airbrake_ms = 1000;
2440 if (poscontrol.get_state() == QPOS_AIRBRAKE &&
2441 poscontrol.time_since_state_start_ms() > min_airbrake_ms &&
2442 (aspeed < aspeed_threshold || // too low airspeed
2443 fabsf(degrees(closing_vel.angle(desired_closing_vel))) > 60 || // wrong direction
2444 closing_speed > MAX(desired_closing_speed*1.2, desired_closing_speed+2) || // too fast
2445 closing_speed < desired_closing_speed*0.5 || // too slow ground speed
2446 labs(plane.ahrs.roll_sensor - plane.nav_roll_cd) > attitude_error_threshold_cd || // bad attitude
2447 labs(plane.ahrs.pitch_sensor - plane.nav_pitch_cd) > attitude_error_threshold_cd)) {
2448 gcs().send_text(MAV_SEVERITY_INFO,"VTOL position1 v=%.1f d=%.1f h=%.1f dc=%.1f",
2449 (double)groundspeed,
2450 (double)plane.auto_state.wp_distance,
2451 plane.relative_ground_altitude(plane.g.rangefinder_landing),
2452 desired_closing_speed);
2453 poscontrol.set_state(QPOS_POSITION1);
2454 transition->set_last_fw_pitch();
2456 // switch to vfwd for throttle control
2457 vel_forward.integrator = SRV_Channels::get_output_scaled(SRV_Channel::k_throttle);
2459 // adjust the initial forward throttle based on our desired and actual closing speed
2460 // this allows for significant initial forward throttle
2461 // when we have a strong headwind, but low throttle in the usual case where
2462 // we want to slow down ready for POSITION2
2463 vel_forward.integrator = linear_interpolate(0, vel_forward.integrator,
2464 closing_speed,
2465 1.2*desired_closing_speed, 0.5*desired_closing_speed);
2467 // limit our initial forward throttle in POSITION1 to be 0.5 of cruise throttle
2468 vel_forward.integrator = constrain_float(vel_forward.integrator, 0, plane.aparm.throttle_cruise*0.5);
2470 vel_forward.last_ms = now_ms;
2473 if (!tiltrotor.enabled() && !tailsitter.enabled()) {
2475 cope with fwd motor thrust loss during approach. We detect
2476 this by looking for the fwd throttle saturating. This only
2477 applies to separate lift-thrust vehicles
2479 bool throttle_saturated = SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) >= plane.aparm.throttle_max;
2480 if (throttle_saturated &&
2481 motors->get_desired_spool_state() < AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED &&
2482 plane.auto_state.sink_rate > 0.2 && aspeed < aspeed_threshold+4) {
2483 if (poscontrol.thrust_loss_start_ms == 0) {
2484 poscontrol.thrust_loss_start_ms = now_ms;
2486 if (now_ms - poscontrol.thrust_loss_start_ms > 5000) {
2487 gcs().send_text(MAV_SEVERITY_INFO,"VTOL pos1 thrust loss as=%.1f at=%.1f",
2488 aspeed, aspeed_threshold);
2489 poscontrol.set_state(QPOS_POSITION1);
2490 transition->set_last_fw_pitch();
2492 } else {
2493 poscontrol.thrust_loss_start_ms = 0;
2496 // handle loss of forward thrust in approach based on low airspeed detection
2497 if (poscontrol.get_state() == QPOS_APPROACH && aspeed < aspeed_threshold &&
2498 motors->get_desired_spool_state() < AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED) {
2499 gcs().send_text(MAV_SEVERITY_INFO,"VTOL pos1 low speed as=%.1f at=%.1f",
2500 aspeed, aspeed_threshold);
2501 poscontrol.set_state(QPOS_POSITION1);
2502 transition->set_last_fw_pitch();
2506 if (poscontrol.get_state() == QPOS_APPROACH) {
2507 poscontrol_init_approach();
2509 break;
2512 case QPOS_POSITION1: {
2513 setup_target_position();
2515 if (tailsitter.enabled() && tailsitter.in_vtol_transition(now_ms)) {
2516 break;
2519 const Vector2f diff_wp = plane.current_loc.get_distance_NE(loc);
2520 const float distance = diff_wp.length();
2521 const Vector2f rel_groundspeed_vector = landing_closing_velocity();
2522 const float rel_groundspeed_sq = rel_groundspeed_vector.length_squared();
2523 float closing_groundspeed = 0;
2525 if (distance > 0.1) {
2526 closing_groundspeed = rel_groundspeed_vector * diff_wp.normalized();
2529 // calculate speed we should be at to reach the position2
2530 // target speed at the position2 distance threshold, assuming
2531 // Q_TRANS_DECEL is correct
2532 const float stopping_speed = safe_sqrt(MAX(0, distance-position2_dist_threshold) * 2 * transition_decel) + position2_target_speed;
2534 float target_speed = stopping_speed;
2536 // maximum configured VTOL speed
2537 const float wp_speed = MAX(1.0, wp_nav->get_default_speed_xy() * 0.01);
2538 const float scaled_wp_speed = get_scaled_wp_speed(degrees(diff_wp.angle()));
2540 // limit target speed to a the pos1 speed limit, which starts out at the initial speed
2541 // but is adjusted if we start putting our nose down. We always allow at least twice
2542 // the WP speed
2543 target_speed = MIN(MAX(poscontrol.pos1_speed_limit, 2*wp_speed), target_speed);
2545 if (poscontrol.reached_wp_speed ||
2546 rel_groundspeed_sq < sq(wp_speed) ||
2547 wp_speed > 1.35*scaled_wp_speed) {
2548 // once we get below the Q_WP_SPEED then we don't want to
2549 // speed up again. At that point we should fly within the
2550 // limits of the configured VTOL controller we also apply
2551 // this limit when we are more than 45 degrees off the
2552 // target in yaw, which is when we start to become
2553 // unstable
2554 target_speed = MIN(target_speed, scaled_wp_speed);
2555 poscontrol.reached_wp_speed = true;
2558 // run fixed wing navigation
2559 plane.nav_controller->update_waypoint(plane.current_loc, loc);
2561 Vector2f target_speed_xy_cms;
2562 Vector2f target_accel_cms;
2563 bool have_target_yaw = false;
2564 float target_yaw_deg;
2565 const float target_accel = MIN(accel_needed(distance, sq(closing_groundspeed)), transition_decel*2);
2566 if (distance > 0.1) {
2567 Vector2f diff_wp_norm = diff_wp.normalized();
2568 target_speed_xy_cms = diff_wp_norm * target_speed * 100;
2569 target_accel_cms = diff_wp_norm * (-target_accel*100);
2570 target_yaw_deg = degrees(diff_wp_norm.angle());
2571 const float yaw_err_deg = wrap_180(target_yaw_deg - degrees(plane.ahrs.get_yaw()));
2572 bool overshoot = (closing_groundspeed < 0 || fabsf(yaw_err_deg) > 60);
2573 if (overshoot && !poscontrol.overshoot) {
2574 gcs().send_text(MAV_SEVERITY_INFO,"VTOL Overshoot d=%.1f cs=%.1f yerr=%.1f",
2575 distance, closing_groundspeed, yaw_err_deg);
2576 poscontrol.overshoot = true;
2577 pos_control->set_accel_desired_xy_cmss(Vector2f());
2579 if (poscontrol.overshoot) {
2580 /* we have overshot the landing point or our nose is
2581 off by more than 60 degrees. Zero target accel and
2582 point nose at the landing point. Set target speed
2583 to our position2 threshold speed
2585 target_accel_cms.zero();
2587 // allow up to the WP speed when we are further away, slowing to the pos2 target speed
2588 // when we are close
2589 target_speed = linear_interpolate(position2_target_speed, wp_speed,
2590 distance,
2591 position2_dist_threshold*1.5,
2592 2*position2_dist_threshold + stopping_distance(rel_groundspeed_sq));
2594 target_speed_xy_cms = diff_wp_norm * target_speed * 100;
2595 have_target_yaw = true;
2597 // adjust target yaw angle for wind. We calculate yaw based on the target speed
2598 // we want assuming no speed scaling due to direction
2599 const Vector2f wind = plane.ahrs.wind_estimate().xy();
2600 const float gnd_speed = plane.ahrs.groundspeed();
2601 Vector2f target_speed_xy = landing_velocity + diff_wp_norm * gnd_speed - wind;
2602 target_yaw_deg = degrees(target_speed_xy.angle());
2605 const float target_speed_ms = target_speed_xy_cms.length() * 0.01;
2607 target_speed_xy_cms += landing_velocity * 100;
2608 poscontrol.target_speed = target_speed_ms;
2609 poscontrol.target_accel = target_accel;
2611 if (!poscontrol.reached_wp_speed &&
2612 rel_groundspeed_sq < sq(target_speed_ms) &&
2613 rel_groundspeed_sq > sq(2*wp_speed) &&
2614 plane.nav_pitch_cd < 0) {
2615 // we have slowed down more than expected, likely due to
2616 // drag from the props and we're starting to put our nose
2617 // down as a result. We want to accept the slowdown and
2618 // re-calculate the target speed profile
2619 poscontrol.pos1_speed_limit = sqrtf(rel_groundspeed_sq);
2622 // use input shaping and abide by accel and jerk limits
2623 pos_control->input_vel_accel_xy(target_speed_xy_cms, target_accel_cms);
2625 // run horizontal velocity controller
2626 run_xy_controller(MAX(target_accel, transition_decel)*1.5);
2628 if (!poscontrol.done_accel_init) {
2630 the pos controller init assumes zero accel, we need to
2631 override that so that we can start decelerating more
2632 quickly at the start of POSITION1
2634 poscontrol.done_accel_init = true;
2635 pos_control->set_accel_desired_xy_cmss(target_accel_cms);
2638 // nav roll and pitch are controller by position controller
2639 plane.nav_roll_cd = pos_control->get_roll_cd();
2640 plane.nav_pitch_cd = pos_control->get_pitch_cd();
2642 assign_tilt_to_fwd_thr();
2644 if (transition->set_VTOL_roll_pitch_limit(plane.nav_roll_cd, plane.nav_pitch_cd)) {
2645 pos_control->set_externally_limited_xy();
2648 // call attitude controller
2649 disable_yaw_rate_time_constant();
2651 // setup scaling of roll and pitch angle P gains to match fixed wing gains
2652 setup_rp_fw_angle_gains();
2654 if (have_target_yaw) {
2655 attitude_control->input_euler_angle_roll_pitch_yaw(plane.nav_roll_cd,
2656 plane.nav_pitch_cd,
2657 target_yaw_deg*100, true);
2658 } else {
2659 attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(plane.nav_roll_cd,
2660 plane.nav_pitch_cd,
2661 desired_auto_yaw_rate_cds() + get_weathervane_yaw_rate_cds());
2663 if ((plane.auto_state.wp_distance < position2_dist_threshold) && tiltrotor.tilt_angle_achieved() &&
2664 fabsf(rel_groundspeed_sq) < sq(3*position2_target_speed)) {
2665 // if continuous tiltrotor only advance to position 2 once tilts have finished moving
2666 poscontrol.set_state(QPOS_POSITION2);
2667 poscontrol.pilot_correction_done = false;
2668 gcs().send_text(MAV_SEVERITY_INFO,"VTOL position2 started v=%.1f d=%.1f h=%.1f",
2669 (double)ahrs.groundspeed(), (double)plane.auto_state.wp_distance,
2670 plane.relative_ground_altitude(plane.g.rangefinder_landing));
2672 break;
2675 case QPOS_POSITION2:
2676 case QPOS_LAND_ABORT:
2677 case QPOS_LAND_DESCEND: {
2678 setup_target_position();
2680 for final land repositioning and descent we run the position controller
2682 Vector2f zero;
2683 Vector2f vel_cms = poscontrol.target_vel_cms.xy() + landing_velocity*100;
2684 pos_control->input_pos_vel_accel_xy(poscontrol.target_cm.xy(), vel_cms, zero);
2686 // also run fixed wing navigation
2687 plane.nav_controller->update_waypoint(plane.current_loc, loc);
2689 update_land_positioning();
2691 run_xy_controller(transition_decel*1.5);
2693 // nav roll and pitch are controlled by position controller
2694 plane.nav_roll_cd = pos_control->get_roll_cd();
2695 plane.nav_pitch_cd = pos_control->get_pitch_cd();
2697 assign_tilt_to_fwd_thr();
2699 if (transition->set_VTOL_roll_pitch_limit(plane.nav_roll_cd, plane.nav_pitch_cd)) {
2700 pos_control->set_externally_limited_xy();
2703 // call attitude controller
2704 set_pilot_yaw_rate_time_constant();
2705 attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(plane.nav_roll_cd,
2706 plane.nav_pitch_cd,
2707 get_pilot_input_yaw_rate_cds() + get_weathervane_yaw_rate_cds());
2708 break;
2711 case QPOS_LAND_FINAL:
2712 update_land_positioning();
2714 // relax when close to the ground
2715 if (should_relax()) {
2716 pos_control->relax_velocity_controller_xy();
2717 } else {
2718 Vector2f zero;
2719 Vector2f vel_cms = poscontrol.target_vel_cms.xy() + landing_velocity*100;
2720 Vector2f rpos;
2721 const uint32_t last_reset_ms = plane.ahrs.getLastPosNorthEastReset(rpos);
2722 /* we use velocity control when we may be touching the
2723 ground or if we've had a position reset from AHRS. This
2724 helps us handle a GPS glitch in the final land phase,
2725 and also prevents trying to reposition after touchdown
2727 if (motors->limit.throttle_lower ||
2728 motors->get_throttle() < 0.5*motors->get_throttle_hover() ||
2729 last_reset_ms != poscontrol.last_pos_reset_ms) {
2730 pos_control->input_vel_accel_xy(vel_cms, zero);
2731 } else {
2732 // otherwise use full pos control
2733 pos_control->input_pos_vel_accel_xy(poscontrol.target_cm.xy(), vel_cms, zero);
2737 run_xy_controller();
2739 // nav roll and pitch are controller by position controller
2740 plane.nav_roll_cd = pos_control->get_roll_cd();
2741 plane.nav_pitch_cd = pos_control->get_pitch_cd();
2743 assign_tilt_to_fwd_thr();
2745 // call attitude controller
2746 set_pilot_yaw_rate_time_constant();
2747 attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(plane.nav_roll_cd,
2748 plane.nav_pitch_cd,
2749 get_pilot_input_yaw_rate_cds() + get_weathervane_yaw_rate_cds());
2750 break;
2752 case QPOS_LAND_COMPLETE:
2753 // nothing to do
2754 break;
2757 // now height control
2758 switch (poscontrol.get_state()) {
2759 case QPOS_NONE:
2760 poscontrol.set_state(QPOS_POSITION1);
2761 INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
2762 break;
2764 case QPOS_APPROACH:
2765 case QPOS_AIRBRAKE:
2766 // we just want stability from the VTOL controller in these
2767 // phases of landing, so relax the Z controller, unless we are
2768 // providing assistance
2769 if (transition->complete()) {
2770 pos_control->relax_z_controller(0);
2772 break;
2773 case QPOS_POSITION1:
2774 if (tailsitter.in_vtol_transition(now_ms)) {
2775 pos_control->relax_z_controller(0);
2776 break;
2778 FALLTHROUGH;
2779 case QPOS_POSITION2: {
2780 bool vtol_loiter_auto = false;
2781 if (plane.control_mode == &plane.mode_auto) {
2782 switch (plane.mission.get_current_nav_cmd().id) {
2783 case MAV_CMD_NAV_LOITER_UNLIM:
2784 case MAV_CMD_NAV_LOITER_TIME:
2785 case MAV_CMD_NAV_LOITER_TURNS:
2786 case MAV_CMD_NAV_LOITER_TO_ALT:
2787 vtol_loiter_auto = true;
2788 break;
2791 if (plane.control_mode == &plane.mode_guided || vtol_loiter_auto) {
2792 plane.ahrs.get_location(plane.current_loc);
2793 int32_t target_altitude_cm;
2794 if (!plane.next_WP_loc.get_alt_cm(Location::AltFrame::ABOVE_ORIGIN,target_altitude_cm)) {
2795 break;
2797 if (poscontrol.slow_descent &&
2798 plane.prev_WP_loc.get_distance(plane.next_WP_loc) > 50) {
2799 // gradually descend as we approach target
2800 plane.auto_state.wp_proportion = plane.current_loc.line_path_proportion(plane.prev_WP_loc, plane.next_WP_loc);
2801 int32_t prev_alt;
2802 if (plane.prev_WP_loc.get_alt_cm(Location::AltFrame::ABOVE_ORIGIN,prev_alt)) {
2803 target_altitude_cm = linear_interpolate(prev_alt,
2804 target_altitude_cm,
2805 plane.auto_state.wp_proportion,
2806 0, 1);
2809 #if AP_TERRAIN_AVAILABLE
2810 float terrain_altitude_offset;
2811 if (plane.next_WP_loc.terrain_alt && plane.terrain.height_terrain_difference_home(terrain_altitude_offset, true)) {
2812 // Climb if current terrain is above home, target_altitude_cm is reltive to home
2813 target_altitude_cm += MAX(terrain_altitude_offset*100,0);
2815 #endif
2816 float zero = 0;
2817 float target_z = target_altitude_cm;
2818 pos_control->input_pos_vel_accel_z(target_z, zero, 0);
2819 } else if (plane.control_mode == &plane.mode_qrtl) {
2820 Location loc2 = loc;
2821 loc2.change_alt_frame(Location::AltFrame::ABOVE_ORIGIN);
2822 float target_z = loc2.alt;
2823 float zero = 0;
2824 pos_control->input_pos_vel_accel_z(target_z, zero, 0);
2825 } else {
2826 set_climb_rate_cms(0);
2828 break;
2831 case QPOS_LAND_DESCEND:
2832 case QPOS_LAND_ABORT:
2833 case QPOS_LAND_FINAL: {
2834 float height_above_ground = plane.relative_ground_altitude(plane.g.rangefinder_landing);
2835 if (poscontrol.get_state() == QPOS_LAND_FINAL) {
2836 if (!option_is_set(QuadPlane::OPTION::DISABLE_GROUND_EFFECT_COMP)) {
2837 ahrs.set_touchdown_expected(true);
2840 if (poscontrol.get_state() == QPOS_LAND_ABORT) {
2841 set_climb_rate_cms(wp_nav->get_default_speed_up());
2842 break;
2844 const float descent_rate_cms = landing_descent_rate_cms(height_above_ground);
2845 pos_control->land_at_climb_rate_cm(-descent_rate_cms, descent_rate_cms>0);
2846 break;
2849 case QPOS_LAND_COMPLETE:
2850 break;
2854 run the z controller unless something has already run it or set a target throttle
2856 if (!suppress_z_controller) {
2857 // otherwise run z controller
2858 run_z_controller();
2861 #if HAL_LOGGING_ENABLED
2862 if (now_ms - poscontrol.last_log_ms >= 40) {
2863 // log poscontrol at 25Hz
2864 poscontrol.last_log_ms = now_ms;
2865 log_QPOS();
2867 #endif
2871 determine which fwd throttle handling method is active
2873 QuadPlane::ActiveFwdThr QuadPlane::get_vfwd_method(void) const
2875 const bool have_fwd_thr_gain = is_positive(q_fwd_thr_gain);
2876 const bool have_vfwd_gain = is_positive(vel_forward.gain);
2878 #if AP_ICENGINE_ENABLED
2879 const auto ice_state = plane.g2.ice_control.get_state();
2880 if (ice_state != AP_ICEngine::ICE_DISABLED && ice_state != AP_ICEngine::ICE_RUNNING) {
2881 // we need the engine running for fwd throttle
2882 return ActiveFwdThr::NONE;
2884 #endif
2886 #if QAUTOTUNE_ENABLED
2887 if (plane.control_mode == &plane.mode_qautotune) {
2888 return ActiveFwdThr::NONE;
2890 #endif
2892 if (have_fwd_thr_gain) {
2893 if (vfwd_enable_active) {
2894 // user has used AUX function to activate new method
2895 return ActiveFwdThr::NEW;
2897 if (q_fwd_thr_use == FwdThrUse::ALL) {
2898 return ActiveFwdThr::NEW;
2900 if (q_fwd_thr_use == FwdThrUse::POSCTRL && pos_control->is_active_xy()) {
2901 return ActiveFwdThr::NEW;
2904 if (have_vfwd_gain && pos_control->is_active_xy()) {
2905 return ActiveFwdThr::OLD;
2907 return ActiveFwdThr::NONE;
2911 map from pitch tilt to fwd throttle when enabled
2913 void QuadPlane::assign_tilt_to_fwd_thr(void) {
2915 const auto fwd_thr_active = get_vfwd_method();
2916 if (fwd_thr_active != ActiveFwdThr::NEW) {
2917 q_fwd_throttle = 0.0f;
2918 q_fwd_pitch_lim_cd = 100.0f * q_fwd_pitch_lim;
2919 return;
2921 // Handle the case where we are limiting the forward pitch angle to prevent negative wing lift
2922 // and are using the forward thrust motor or tilting rotors to provide the forward acceleration
2923 float fwd_tilt_rad = radians(constrain_float(-0.01f * (float)plane.nav_pitch_cd, 0.0f, 45.0f));
2924 q_fwd_throttle = MIN(q_fwd_thr_gain * tanf(fwd_tilt_rad), 1.0f);
2926 // Relax forward tilt limit if the position controller is saturating in the forward direction because
2927 // the forward thrust motor could be failed. Do not do this with tilt rotors because they do not rely on
2928 // forward throttle during VTOL flight
2929 if (!tiltrotor.enabled()) {
2930 const float fwd_tilt_range_cd = (float)aparm.angle_max - 100.0f * q_fwd_pitch_lim;
2931 if (is_positive(fwd_tilt_range_cd)) {
2932 // rate limit the forward tilt change to slew between the motor good and motor failed
2933 // value over 10 seconds
2934 const bool fwd_limited = plane.quadplane.pos_control->is_active_xy() and plane.quadplane.pos_control->get_fwd_pitch_is_limited();
2935 const float fwd_pitch_lim_cd_tgt = fwd_limited ? (float)aparm.angle_max : 100.0f * q_fwd_pitch_lim;
2936 const float delta_max = 0.1f * fwd_tilt_range_cd * plane.G_Dt;
2937 q_fwd_pitch_lim_cd += constrain_float((fwd_pitch_lim_cd_tgt - q_fwd_pitch_lim_cd), -delta_max, delta_max);
2938 // Don't let the forward pitch limit be more than the forward pitch demand before limiting to
2939 // avoid opening up the limit more than necessary
2940 q_fwd_pitch_lim_cd = MIN(q_fwd_pitch_lim_cd, MAX(-(float)plane.nav_pitch_cd, 100.0f * q_fwd_pitch_lim));
2941 } else {
2942 // take the lesser of the two limits
2943 q_fwd_pitch_lim_cd = (float)aparm.angle_max;
2947 // Prevent the wing from being overloaded when braking from high speed in a VTOL mode
2948 float nav_pitch_upper_limit_cd = 100.0f * q_bck_pitch_lim;
2949 float aspeed;
2950 if (is_positive(q_bck_pitch_lim) && ahrs.airspeed_estimate(aspeed)) {
2951 const float reference_speed = MAX(plane.aparm.airspeed_min, MIN_AIRSPEED_MIN);
2952 float speed_scaler = sq(reference_speed / MAX(aspeed, 0.1f));
2953 nav_pitch_upper_limit_cd *= speed_scaler;
2954 nav_pitch_upper_limit_cd = MIN(nav_pitch_upper_limit_cd, (float)aparm.angle_max);
2956 const float tconst = 0.5f;
2957 const float dt = AP_HAL::millis() - q_pitch_limit_update_ms;
2958 q_pitch_limit_update_ms = AP_HAL::millis();
2959 if (is_positive(dt)) {
2960 const float coef = dt / (dt + tconst);
2961 q_bck_pitch_lim_cd = (1.0f - coef) * q_bck_pitch_lim_cd + coef * nav_pitch_upper_limit_cd;
2964 plane.nav_pitch_cd = MIN(plane.nav_pitch_cd, (int32_t)q_bck_pitch_lim_cd);
2966 #if HAL_LOGGING_ENABLED
2967 AP::logger().WriteStreaming("QBRK",
2968 "TimeUS,SpdScaler,NPULCD,QBPLCD,NPCD", // labels
2969 "Qffii", // fmt
2970 AP_HAL::micros64(),
2971 (double)speed_scaler,
2972 (double)nav_pitch_upper_limit_cd,
2973 (int32_t)q_bck_pitch_lim_cd,
2974 (int32_t)plane.nav_pitch_cd);
2975 #endif
2978 float fwd_thr_scaler;
2979 if (!in_vtol_land_approach()) {
2980 // To prevent forward motor prop strike, reduce throttle to zero when close to ground.
2981 float alt_cutoff = MAX(0,vel_forward_alt_cutoff);
2982 float height_above_ground = plane.relative_ground_altitude(plane.g.rangefinder_landing);
2983 fwd_thr_scaler = linear_interpolate(0.0f, 1.0f, height_above_ground, alt_cutoff, alt_cutoff+2);
2984 } else {
2985 // When we are doing horizontal positioning in a VTOL land we always allow the fwd motor
2986 // to run. Otherwise a bad height above landing point estimate could cause the aircraft
2987 // not to be able to approach the landing point
2988 fwd_thr_scaler = 1.0f;
2990 q_fwd_throttle *= fwd_thr_scaler;
2992 // When reducing forward throttle use, relax lower pitch limit to maintain forward
2993 // acceleration capability.
2994 const float nav_pitch_lower_limit_cd = - (int32_t)((float)aparm.angle_max * (1.0f - fwd_thr_scaler) + q_fwd_pitch_lim_cd * fwd_thr_scaler);
2996 #if HAL_LOGGING_ENABLED
2997 // Diagnostics logging - remove when feature is fully flight tested.
2998 AP::logger().WriteStreaming("FWDT",
2999 "TimeUS,fts,qfplcd,npllcd,npcd,qft,npulcd", // labels
3000 "Qffffff", // fmt
3001 AP_HAL::micros64(),
3002 (double)fwd_thr_scaler,
3003 (double)q_fwd_pitch_lim_cd,
3004 (double)nav_pitch_lower_limit_cd,
3005 (double)plane.nav_pitch_cd,
3006 (double)q_fwd_throttle,
3007 (float)nav_pitch_upper_limit_cd);
3008 #endif
3010 plane.nav_pitch_cd = MAX(plane.nav_pitch_cd, (int32_t)nav_pitch_lower_limit_cd);
3014 we want to limit WP speed to a lower speed when more than 20 degrees
3015 off pointing at the destination. quadplanes are often
3016 unstable when flying sideways or backwards
3018 float QuadPlane::get_scaled_wp_speed(float target_bearing_deg) const
3020 const float yaw_difference = fabsf(wrap_180(degrees(plane.ahrs.get_yaw()) - target_bearing_deg));
3021 const float wp_speed = wp_nav->get_default_speed_xy() * 0.01;
3022 if (yaw_difference > 20) {
3023 // this gives a factor of 2x reduction in max speed when
3024 // off by 90 degrees, and 3x when off by 180 degrees
3025 const float speed_reduction = linear_interpolate(1, 3,
3026 yaw_difference,
3027 20, 160);
3028 return wp_speed / speed_reduction;
3030 return wp_speed;
3034 setup the target position based on plane.next_WP_loc
3036 void QuadPlane::setup_target_position(void)
3038 const Location &loc = plane.next_WP_loc;
3039 Location origin;
3040 if (!ahrs.get_origin(origin)) {
3041 origin.zero();
3043 if (!in_vtol_land_approach() || poscontrol.get_state() > QPOS_APPROACH) {
3044 set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
3047 Vector2f diff2d = origin.get_distance_NE(loc);
3048 diff2d += poscontrol.xy_correction;
3049 poscontrol.target_cm.x = diff2d.x * 100;
3050 poscontrol.target_cm.y = diff2d.y * 100;
3051 poscontrol.target_cm.z = plane.next_WP_loc.alt - origin.alt;
3053 // set vertical speed and acceleration limits
3054 pos_control->set_max_speed_accel_z(-get_pilot_velocity_z_max_dn(), pilot_speed_z_max_up*100, pilot_accel_z*100);
3055 pos_control->set_correction_speed_accel_z(-get_pilot_velocity_z_max_dn(), pilot_speed_z_max_up*100, pilot_accel_z*100);
3059 run takeoff controller to climb vertically
3061 void QuadPlane::takeoff_controller(void)
3063 // reset fixed wing controller to neutral as base output
3064 plane.nav_roll_cd = 0;
3065 plane.nav_pitch_cd = 0;
3067 if (!plane.arming.is_armed_and_safety_off()) {
3068 return;
3071 uint32_t now = AP_HAL::millis();
3072 const auto spool_state = motors->get_desired_spool_state();
3073 if (plane.control_mode == &plane.mode_guided && guided_takeoff
3074 && tiltrotor.enabled() && !tiltrotor.fully_up() &&
3075 spool_state != AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED) {
3076 // waiting for motors to tilt up
3077 takeoff_start_time_ms = now;
3078 return;
3081 // don't takeoff up until rudder is re-centered after rudder arming
3082 if (plane.arming.last_arm_method() == AP_Arming::Method::RUDDER &&
3083 (takeoff_last_run_ms == 0 ||
3084 now - takeoff_last_run_ms > 1000) &&
3085 !plane.seen_neutral_rudder &&
3086 spool_state <= AP_Motors::DesiredSpoolState::GROUND_IDLE) {
3087 // start motor spinning if not spinning already so user sees it is armed
3088 set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
3089 takeoff_start_time_ms = now;
3090 if (now - plane.takeoff_state.rudder_takeoff_warn_ms > TAKEOFF_RUDDER_WARNING_TIMEOUT) {
3091 gcs().send_text(MAV_SEVERITY_WARNING, "Takeoff waiting for rudder release");
3092 plane.takeoff_state.rudder_takeoff_warn_ms = now;
3094 return;
3099 for takeoff we use the position controller
3101 setup_target_position();
3103 // set position control target and update
3105 Vector2f vel, zero;
3106 if (AP_HAL::millis() - poscontrol.last_velocity_match_ms < 1000) {
3107 vel = poscontrol.velocity_match * 100;
3111 support zeroing roll/pitch during early part of takeoff. This
3112 can help particularly with poor GPS velocity data
3114 bool no_navigation = false;
3115 if (takeoff_navalt_min > 0) {
3116 const float alt = plane.current_loc.alt*0.01;
3117 if (takeoff_last_run_ms == 0 ||
3118 now - takeoff_last_run_ms > 1000) {
3119 takeoff_start_alt = alt;
3121 if (alt - takeoff_start_alt < takeoff_navalt_min) {
3122 no_navigation = true;
3125 takeoff_last_run_ms = now;
3127 if (no_navigation) {
3128 pos_control->relax_velocity_controller_xy();
3129 } else {
3130 pos_control->set_accel_desired_xy_cmss(zero);
3131 pos_control->set_vel_desired_xy_cms(vel);
3132 pos_control->input_vel_accel_xy(vel, zero);
3134 // nav roll and pitch are controller by position controller
3135 plane.nav_roll_cd = pos_control->get_roll_cd();
3136 plane.nav_pitch_cd = pos_control->get_pitch_cd();
3138 assign_tilt_to_fwd_thr();
3141 run_xy_controller();
3143 set_pilot_yaw_rate_time_constant();
3144 attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(plane.nav_roll_cd,
3145 plane.nav_pitch_cd,
3146 get_pilot_input_yaw_rate_cds() + get_weathervane_yaw_rate_cds());
3148 float vel_z = wp_nav->get_default_speed_up();
3149 if (plane.control_mode == &plane.mode_guided && guided_takeoff) {
3150 // for guided takeoff we aim for a specific height with zero
3151 // velocity at that height
3152 Location origin;
3153 if (ahrs.get_origin(origin)) {
3154 // a small margin to ensure we do move to the next takeoff
3155 // stage
3156 const int32_t margin_cm = 5;
3157 float pos_z = margin_cm + plane.next_WP_loc.alt - origin.alt;
3158 vel_z = 0;
3159 pos_control->input_pos_vel_accel_z(pos_z, vel_z, 0);
3160 } else {
3161 set_climb_rate_cms(vel_z);
3163 } else {
3164 set_climb_rate_cms(vel_z);
3167 run_z_controller();
3171 run waypoint controller between prev_WP_loc and next_WP_loc
3173 void QuadPlane::waypoint_controller(void)
3175 setup_target_position();
3177 const Location &loc = plane.next_WP_loc;
3178 const uint32_t now = AP_HAL::millis();
3179 if (!loc.same_loc_as(last_auto_target) ||
3180 now - last_loiter_ms > 500) {
3181 wp_nav->set_wp_destination(poscontrol.target_cm.tofloat());
3182 last_auto_target = loc;
3184 last_loiter_ms = now;
3187 this is full copter control of auto flight
3189 // run wpnav controller
3190 wp_nav->update_wpnav();
3192 // nav roll and pitch are controller by waypoint controller
3193 plane.nav_roll_cd = wp_nav->get_roll();
3194 plane.nav_pitch_cd = wp_nav->get_pitch();
3196 assign_tilt_to_fwd_thr();
3198 if (transition->set_VTOL_roll_pitch_limit(plane.nav_roll_cd, plane.nav_pitch_cd)) {
3199 pos_control->set_externally_limited_xy();
3202 // call attitude controller
3203 disable_yaw_rate_time_constant();
3204 attitude_control->input_euler_angle_roll_pitch_yaw(plane.nav_roll_cd,
3205 plane.nav_pitch_cd,
3206 wp_nav->get_yaw(),
3207 true);
3209 // climb based on altitude error
3210 set_climb_rate_cms(assist_climb_rate_cms());
3211 run_z_controller();
3216 handle auto-mode when auto_state.vtol_mode is true
3218 void QuadPlane::control_auto(void)
3220 if (!setup()) {
3221 return;
3224 if (poscontrol.get_state() > QPOS_APPROACH) {
3225 bool should_run_motors = false;
3227 // don't run the motors if in an arming delay
3228 if (plane.arming.get_delay_arming()) {
3229 should_run_motors = false;
3232 // don't run motors if we are in the wait state for payload place
3233 if (motors->get_desired_spool_state() == AP_Motors::DesiredSpoolState::SHUT_DOWN &&
3234 plane.in_auto_mission_id(MAV_CMD_NAV_PAYLOAD_PLACE) &&
3235 poscontrol.get_state() == QPOS_LAND_COMPLETE) {
3236 should_run_motors = false;
3239 if (should_run_motors) {
3240 set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
3244 uint16_t id = plane.mission.get_current_nav_cmd().id;
3245 switch (id) {
3246 case MAV_CMD_NAV_VTOL_TAKEOFF:
3247 case MAV_CMD_NAV_TAKEOFF:
3248 if (is_vtol_takeoff(id)) {
3249 takeoff_controller();
3251 break;
3252 case MAV_CMD_NAV_VTOL_LAND:
3253 case MAV_CMD_NAV_PAYLOAD_PLACE:
3254 case MAV_CMD_NAV_LAND:
3255 if (is_vtol_land(id)) {
3256 vtol_position_controller();
3258 break;
3259 case MAV_CMD_NAV_LOITER_UNLIM:
3260 case MAV_CMD_NAV_LOITER_TIME:
3261 case MAV_CMD_NAV_LOITER_TURNS:
3262 case MAV_CMD_NAV_LOITER_TO_ALT: {
3263 const uint32_t now = AP_HAL::millis();
3264 if (now - poscontrol.last_run_ms > 100) {
3265 // ensure that poscontrol is reset
3266 poscontrol.set_state(QPOS_POSITION1);
3268 vtol_position_controller();
3270 break;
3271 default:
3272 waypoint_controller();
3273 break;
3278 start a VTOL takeoff
3280 bool QuadPlane::do_vtol_takeoff(const AP_Mission::Mission_Command& cmd)
3282 if (!setup()) {
3283 return false;
3286 // we always use the current location in XY for takeoff. The altitude defaults
3287 // to relative to current height, but if Q_OPTIONS is set to respect takeoff frame
3288 // then it will use normal frame handling for height
3289 Location loc = cmd.content.location;
3290 loc.lat = 0;
3291 loc.lng = 0;
3292 plane.set_next_WP(loc);
3293 if (option_is_set(QuadPlane::OPTION::RESPECT_TAKEOFF_FRAME)) {
3294 if (plane.current_loc.alt >= plane.next_WP_loc.alt) {
3295 // we are above the takeoff already, no need to do anything
3296 return false;
3298 } else {
3299 plane.next_WP_loc.alt = plane.current_loc.alt + cmd.content.location.alt;
3301 throttle_wait = false;
3303 // set vertical speed and acceleration limits
3304 pos_control->set_max_speed_accel_z(-get_pilot_velocity_z_max_dn(), pilot_speed_z_max_up*100, pilot_accel_z*100);
3305 pos_control->set_correction_speed_accel_z(-get_pilot_velocity_z_max_dn(), pilot_speed_z_max_up*100, pilot_accel_z*100);
3307 // initialise the vertical position controller
3308 pos_control->init_z_controller();
3310 // also update nav_controller for status output
3311 plane.nav_controller->update_waypoint(plane.current_loc, plane.next_WP_loc);
3313 // calculate the time required to complete a takeoff
3314 // this may be conservative and accept extra time due to clamping
3315 // derived from the following latex equations if you want a nicely formatted view
3316 // t_{accel} = \frac{V_max - V_z}{a}
3317 // d_{accel} = V_z*t_{accel} + \frac{1}{2}*a*t_{accel}^2
3318 // d_{remaining} = d_{total} - d_{accel}
3319 // t_{constant} = \frac{d_{remaining}}{V_z}
3320 // t = max(t_{accel}, 0) + max(t_{constant}, 0)
3321 const float d_total = (plane.next_WP_loc.alt - plane.current_loc.alt) * 0.01f;
3322 const float accel_m_s_s = MAX(0.1, pilot_accel_z);
3323 const float vel_max = MAX(0.1, pilot_speed_z_max_up);
3324 const float vel_z = inertial_nav.get_velocity_z_up_cms() * 0.01f;
3325 const float t_accel = (vel_max - vel_z) / accel_m_s_s;
3326 const float d_accel = vel_z * t_accel + 0.5f * accel_m_s_s * sq(t_accel);
3327 const float d_remaining = d_total - d_accel;
3328 const float t_constant = d_remaining / vel_max;
3329 const float travel_time = MAX(t_accel, 0) + MAX(t_constant, 0);
3331 // setup the takeoff failure handling code
3332 takeoff_start_time_ms = millis();
3333 takeoff_time_limit_ms = MAX(travel_time * takeoff_failure_scalar * 1000, 5000); // minimum time 5 seconds
3335 return true;
3340 start a VTOL landing
3342 bool QuadPlane::do_vtol_land(const AP_Mission::Mission_Command& cmd)
3344 if (!setup()) {
3345 return false;
3348 plane.set_next_WP(cmd.content.location);
3349 // initially aim for current altitude
3350 plane.next_WP_loc.alt = plane.current_loc.alt;
3352 // initialise the position controller
3353 pos_control->init_xy_controller();
3354 pos_control->init_z_controller();
3356 throttle_wait = false;
3357 landing_detect.lower_limit_start_ms = 0;
3358 landing_detect.land_start_ms = 0;
3360 plane.crash_state.is_crashed = false;
3362 // also update nav_controller for status output
3363 plane.nav_controller->update_waypoint(plane.auto_state.crosstrack ? plane.prev_WP_loc : plane.current_loc,
3364 plane.next_WP_loc);
3366 poscontrol_init_approach();
3367 return true;
3371 check if a VTOL takeoff has completed
3373 bool QuadPlane::verify_vtol_takeoff(const AP_Mission::Mission_Command &cmd)
3375 if (!available()) {
3376 return true;
3379 const uint32_t now = millis();
3381 // reset takeoff if we aren't armed
3382 if (!plane.arming.is_armed_and_safety_off()) {
3383 do_vtol_takeoff(cmd);
3384 return false;
3387 if (now - takeoff_start_time_ms < 3000 &&
3388 !option_is_set(QuadPlane::OPTION::DISABLE_GROUND_EFFECT_COMP)) {
3389 ahrs.set_takeoff_expected(true);
3392 // check for failure conditions
3393 if (is_positive(takeoff_failure_scalar) && ((now - takeoff_start_time_ms) > takeoff_time_limit_ms)) {
3394 gcs().send_text(MAV_SEVERITY_CRITICAL, "Failed to complete takeoff within time limit");
3395 plane.set_mode(plane.mode_qland, ModeReason::VTOL_FAILED_TAKEOFF);
3396 return false;
3399 #if AP_AIRSPEED_ENABLED
3400 if (is_positive(maximum_takeoff_airspeed) && (plane.airspeed.get_airspeed() > maximum_takeoff_airspeed)) {
3401 gcs().send_text(MAV_SEVERITY_CRITICAL, "Failed to complete takeoff, excessive wind");
3402 plane.set_mode(plane.mode_qland, ModeReason::VTOL_FAILED_TAKEOFF);
3403 return false;
3405 #endif
3407 if (plane.current_loc.alt < plane.next_WP_loc.alt) {
3408 return false;
3410 transition->restart();
3411 plane.TECS_controller.set_pitch_max_limit(transition_pitch_max);
3413 // todo: why are you doing this, I want to delete it.
3414 set_alt_target_current();
3416 #if AP_FENCE_ENABLED
3417 plane.fence.auto_enable_fence_after_takeoff();
3418 #endif
3420 if (plane.control_mode == &plane.mode_auto) {
3421 // we reset TECS so that the target height filter is not
3422 // constrained by the climb and sink rates from the initial
3423 // takeoff height.
3424 plane.TECS_controller.reset();
3427 // don't crosstrack on next WP
3428 plane.auto_state.next_wp_crosstrack = false;
3430 return true;
3434 a landing detector based on change in altitude over a timeout
3436 bool QuadPlane::land_detector(uint32_t timeout_ms)
3438 bool might_be_landed = should_relax() && !poscontrol.pilot_correction_active;
3439 if (!might_be_landed) {
3440 landing_detect.land_start_ms = 0;
3441 return false;
3443 const uint32_t now = AP_HAL::millis();
3444 float height = inertial_nav.get_position_z_up_cm() * 0.01;
3445 if (landing_detect.land_start_ms == 0) {
3446 landing_detect.land_start_ms = now;
3447 landing_detect.vpos_start_m = height;
3450 // we only consider the vehicle landed when the motors have been
3451 // at minimum for timeout_ms+1000 and the vertical position estimate has not
3452 // changed by more than 20cm for timeout_ms
3453 if (fabsf(height - landing_detect.vpos_start_m) > landing_detect.detect_alt_change) {
3454 // height has changed, call off landing detection
3455 landing_detect.land_start_ms = 0;
3456 return false;
3459 if ((now - landing_detect.land_start_ms) < timeout_ms ||
3460 (now - landing_detect.lower_limit_start_ms) < (timeout_ms+1000)) {
3461 // not landed yet
3462 return false;
3465 return true;
3469 check if a landing is complete
3471 bool QuadPlane::check_land_complete(void)
3473 if (poscontrol.get_state() != QPOS_LAND_FINAL) {
3474 // only apply to final landing phase
3475 return false;
3477 if (land_detector(4000)) {
3478 poscontrol.set_state(QPOS_LAND_COMPLETE);
3479 gcs().send_text(MAV_SEVERITY_INFO,"Land complete");
3481 if (plane.in_auto_mission_id(MAV_CMD_NAV_PAYLOAD_PLACE)) {
3482 // for payload place with full landing we shutdown motors
3483 // and wait for the lua script to trigger a climb (using
3484 // landing abort) or disarm
3485 set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN);
3486 return false;
3489 if (plane.control_mode != &plane.mode_auto ||
3490 !plane.mission.continue_after_land()) {
3491 // disarm on land unless we have MIS_OPTIONS setup to
3492 // continue after land in AUTO
3493 plane.arming.disarm(AP_Arming::Method::LANDED);
3495 return true;
3497 return false;
3502 check if we should switch from QPOS_LAND_DESCEND to QPOS_LAND_FINAL
3504 bool QuadPlane::check_land_final(void)
3506 float height_above_ground = plane.relative_ground_altitude(plane.g.rangefinder_landing);
3507 // we require 2 readings at 10Hz to be within 5m of each other to
3508 // trigger the switch to land final. This prevents a short term
3509 // glitch at high altitude from triggering land final
3510 const float max_change = 5;
3511 if (height_above_ground < land_final_alt &&
3512 fabsf(height_above_ground - last_land_final_agl) < max_change) {
3513 return true;
3515 last_land_final_agl = height_above_ground;
3518 also apply landing detector, in case we have landed in descent
3519 phase. Use a longer threshold
3521 return land_detector(6000);
3525 check if a VTOL landing has completed
3527 bool QuadPlane::verify_vtol_land(void)
3529 if (!available()) {
3530 return true;
3533 if (poscontrol.get_state() == QPOS_POSITION2) {
3534 // see if we should move onto the descend stage of landing
3535 const float descend_dist_threshold = 2.0;
3536 const float descend_speed_threshold = 3.0;
3537 bool reached_position = false;
3538 if (poscontrol.pilot_correction_done) {
3539 reached_position = !poscontrol.pilot_correction_active;
3540 } else {
3541 const float dist = (inertial_nav.get_position_neu_cm().topostype() - poscontrol.target_cm).xy().length() * 0.01;
3542 reached_position = dist < descend_dist_threshold;
3544 Vector2f target_vel;
3545 if (AP_HAL::millis() - poscontrol.last_velocity_match_ms < 1000) {
3546 target_vel = poscontrol.velocity_match;
3548 Vector3f vel_ned;
3549 UNUSED_RESULT(plane.ahrs.get_velocity_NED(vel_ned));
3551 if (reached_position &&
3552 (vel_ned.xy() - target_vel).length() < descend_speed_threshold) {
3553 poscontrol.set_state(QPOS_LAND_DESCEND);
3554 poscontrol.pilot_correction_done = false;
3555 pos_control->set_lean_angle_max_cd(0);
3556 poscontrol.xy_correction.zero();
3557 #if AP_FENCE_ENABLED
3558 plane.fence.auto_disable_fence_for_landing();
3559 #endif
3560 #if AP_LANDINGGEAR_ENABLED
3561 plane.g2.landing_gear.deploy_for_landing();
3562 #endif
3563 last_land_final_agl = plane.relative_ground_altitude(plane.g.rangefinder_landing);
3564 gcs().send_text(MAV_SEVERITY_INFO,"Land descend started");
3565 if (plane.control_mode == &plane.mode_auto) {
3566 // set height to mission height, so we can use the mission
3567 // WP height for triggering land final if no rangefinder
3568 // available
3569 plane.set_next_WP(plane.mission.get_current_nav_cmd().content.location);
3570 } else {
3571 plane.set_next_WP(plane.next_WP_loc);
3572 plane.next_WP_loc.alt = ahrs.get_home().alt;
3577 // at land_final_alt begin final landing
3578 if (poscontrol.get_state() == QPOS_LAND_DESCEND && check_land_final()) {
3579 poscontrol.set_state(QPOS_LAND_FINAL);
3581 #if AP_ICENGINE_ENABLED
3582 // cut IC engine if enabled
3583 if (land_icengine_cut != 0) {
3584 plane.g2.ice_control.engine_control(0, 0, 0, false);
3586 #endif // AP_ICENGINE_ENABLED
3587 gcs().send_text(MAV_SEVERITY_INFO,"Land final started");
3590 // at land_final_alt begin final landing
3591 if (poscontrol.get_state() == QPOS_LAND_ABORT &&
3592 plane.current_loc.alt*0.01 >= land_descend_start_alt) {
3593 // continue to next WP, if there is one
3594 return true;
3597 if (plane.in_auto_mission_id(MAV_CMD_NAV_PAYLOAD_PLACE) &&
3598 (poscontrol.get_state() == QPOS_LAND_DESCEND ||
3599 poscontrol.get_state() == QPOS_LAND_FINAL)) {
3600 const auto &cmd = plane.mission.get_current_nav_cmd();
3601 if (cmd.p1 > 0 && plane.current_loc.alt*0.01 < land_descend_start_alt - cmd.p1*0.01) {
3602 gcs().send_text(MAV_SEVERITY_INFO,"Payload place aborted");
3603 poscontrol.set_state(QPOS_LAND_ABORT);
3607 if (check_land_complete() && plane.mission.continue_after_land()) {
3608 gcs().send_text(MAV_SEVERITY_INFO,"Mission continue");
3609 return true;
3611 return false;
3614 #if HAL_LOGGING_ENABLED
3615 // Write a control tuning packet
3616 void QuadPlane::Log_Write_QControl_Tuning()
3618 float des_alt_m = 0.0f;
3619 int16_t target_climb_rate_cms = 0;
3620 if (plane.control_mode != &plane.mode_qstabilize) {
3621 des_alt_m = pos_control->get_pos_target_z_cm() * 0.01f;
3622 target_climb_rate_cms = pos_control->get_vel_target_z_cms();
3625 // Asemble assistance bitmask, defintion here is used to generate log documentation
3626 enum class log_assistance_flags {
3627 in_assisted_flight = 1U<<0, // true if VTOL assist is active
3628 forced = 1U<<1, // true if assistance is forced
3629 speed = 1U<<2, // true if assistance due to low airspeed
3630 alt = 1U<<3, // true if assistance due to low altitude
3631 angle = 1U<<4, // true if assistance due to attitude error
3634 uint8_t assist_flags = 0;
3635 if (assisted_flight) {
3636 assist_flags |= (uint8_t)log_assistance_flags::in_assisted_flight;
3638 if (assist.in_force_assist()) {
3639 assist_flags |= (uint8_t)log_assistance_flags::forced;
3641 if (assist.in_speed_assist()) {
3642 assist_flags |= (uint8_t)log_assistance_flags::speed;
3644 if (assist.in_alt_assist()) {
3645 assist_flags |= (uint8_t)log_assistance_flags::alt;
3647 if (assist.in_angle_assist()) {
3648 assist_flags |= (uint8_t)log_assistance_flags::angle;
3651 struct log_QControl_Tuning pkt = {
3652 LOG_PACKET_HEADER_INIT(LOG_QTUN_MSG),
3653 time_us : AP_HAL::micros64(),
3654 throttle_in : attitude_control->get_throttle_in(),
3655 angle_boost : attitude_control->angle_boost(),
3656 throttle_out : motors->get_throttle(),
3657 throttle_hover : motors->get_throttle_hover(),
3658 desired_alt : des_alt_m,
3659 inav_alt : inertial_nav.get_position_z_up_cm() * 0.01f,
3660 baro_alt : int32_t(plane.barometer.get_altitude() * 100),
3661 target_climb_rate : target_climb_rate_cms,
3662 climb_rate : int16_t(inertial_nav.get_velocity_z_up_cms()),
3663 throttle_mix : attitude_control->get_throttle_mix(),
3664 transition_state : transition->get_log_transition_state(),
3665 assist : assist_flags,
3667 plane.logger.WriteBlock(&pkt, sizeof(pkt));
3669 // write multicopter position control message
3670 pos_control->write_log();
3672 // Write tiltrotor tilt angle log
3673 tiltrotor.write_log();
3675 #endif
3679 calculate the forward throttle percentage. The forward throttle can
3680 be used to assist with position hold and with landing approach. It
3681 reduces the need for down pitch which reduces load on the vertical
3682 lift motors.
3684 float QuadPlane::forward_throttle_pct()
3686 // handle special case where forward thrust motor is used instead of forward pitch.
3687 if (get_vfwd_method() == ActiveFwdThr::NEW) {
3688 return 100.0f * q_fwd_throttle;
3692 Unless an RC channel is assigned for manual forward throttle control,
3693 we don't use forward throttle in QHOVER or QSTABILIZE as they are the primary
3694 recovery modes for a quadplane and need to be as simple as
3695 possible. They will drift with the wind.
3697 if (plane.control_mode == &plane.mode_qacro ||
3698 plane.control_mode == &plane.mode_qstabilize ||
3699 plane.control_mode == &plane.mode_qhover) {
3701 if (rc_fwd_thr_ch == nullptr) {
3702 return 0;
3703 } else {
3704 // calculate fwd throttle demand from manual input
3705 float fwd_thr = rc_fwd_thr_ch->percent_input();
3707 // set forward throttle to fwd_thr_max * (manual input + mix): range [0,100]
3708 fwd_thr *= .01f * constrain_float(fwd_thr_max, 0, 100);
3709 return fwd_thr;
3714 see if the controller should be active
3716 if (get_vfwd_method() != ActiveFwdThr::OLD) {
3717 return 0;
3721 in modes with a velocity controller
3723 float deltat = (AP_HAL::millis() - vel_forward.last_ms) * 0.001f;
3724 if (deltat > 1 || deltat < 0) {
3725 vel_forward.integrator = 0;
3726 deltat = 0.1;
3728 if (deltat < 0.1) {
3729 // run at 10Hz
3730 return vel_forward.last_pct;
3732 vel_forward.last_ms = AP_HAL::millis();
3734 // work out the desired speed in forward direction
3735 Vector3f desired_velocity_cms = pos_control->get_vel_desired_cms();
3737 // convert to NED m/s
3738 desired_velocity_cms.z *= -1;
3740 Vector3f vel_ned;
3741 if (!plane.ahrs.get_velocity_NED(vel_ned)) {
3742 // we don't know our velocity? EKF must be pretty sick
3743 vel_forward.last_pct = 0;
3744 vel_forward.integrator = 0;
3745 return 0;
3747 // get component of velocity error in fwd body frame direction
3748 Vector3f vel_error_body = ahrs.get_rotation_body_to_ned().transposed() * ((desired_velocity_cms*0.01f) - vel_ned);
3750 float fwd_vel_error = vel_error_body.x;
3752 // scale forward velocity error by maximum airspeed
3753 fwd_vel_error /= MAX(plane.aparm.airspeed_max, 5);
3755 // add in a component from our current pitch demand. This tends to
3756 // move us to zero pitch. Assume that LIM_PITCH would give us the
3757 // WP nav speed.
3758 fwd_vel_error -= (wp_nav->get_default_speed_xy() * 0.01f) * plane.nav_pitch_cd / (plane.aparm.pitch_limit_max*100);
3760 if (should_relax() && vel_ned.length() < 1) {
3761 // we may be landed
3762 fwd_vel_error = 0;
3763 vel_forward.integrator *= 0.95f;
3766 // integrator as throttle percentage (-100 to 100)
3767 vel_forward.integrator += fwd_vel_error * deltat * vel_forward.gain * 100;
3769 // inhibit reverse throttle and allow petrol engines with min > 0
3770 int8_t fwd_throttle_min = plane.have_reverse_thrust() ? 0 : plane.aparm.throttle_min;
3771 vel_forward.integrator = constrain_float(vel_forward.integrator, fwd_throttle_min, plane.aparm.throttle_cruise);
3773 if (in_vtol_land_approach()) {
3774 // when we are doing horizontal positioning in a VTOL land
3775 // we always allow the fwd motor to run. Otherwise a bad
3776 // lidar could cause the aircraft not to be able to
3777 // approach the landing point when landing below the takeoff point
3778 vel_forward.last_pct = vel_forward.integrator;
3779 } else if ((in_vtol_land_final() && motors->limit.throttle_lower) ||
3780 (plane.g.rangefinder_landing && (plane.rangefinder.status_orient(ROTATION_PITCH_270) == RangeFinder::Status::OutOfRangeLow))) {
3781 // we're in the settling phase of landing or using a rangefinder that is out of range low, disable fwd motor
3782 vel_forward.last_pct = 0;
3783 vel_forward.integrator = 0;
3784 } else {
3785 // If we are below alt_cutoff then scale down the effect until
3786 // it turns off at alt_cutoff and decay the integrator
3787 float alt_cutoff = MAX(0,vel_forward_alt_cutoff);
3788 float height_above_ground = plane.relative_ground_altitude(plane.g.rangefinder_landing);
3790 vel_forward.last_pct = linear_interpolate(0, vel_forward.integrator,
3791 height_above_ground, alt_cutoff, alt_cutoff+2);
3793 if (is_zero(vel_forward.last_pct)) {
3794 // if the percent is 0 then decay the integrator
3795 vel_forward.integrator *= 0.95f;
3798 return vel_forward.last_pct;
3802 get weathervaning yaw rate in cd/s
3804 float QuadPlane::get_weathervane_yaw_rate_cds(void)
3807 we only do weathervaning in modes where we are doing VTOL
3808 position control.
3810 if (!in_vtol_mode() ||
3811 !transition->allow_weathervane() ||
3812 !motors->armed() || (motors->get_desired_spool_state() != AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED) ||
3813 plane.control_mode == &plane.mode_qstabilize ||
3814 #if QAUTOTUNE_ENABLED
3815 plane.control_mode == &plane.mode_qautotune ||
3816 #endif
3817 plane.control_mode == &plane.mode_qhover ||
3818 should_relax()
3820 // Ensure the weathervane controller is reset to prevent weathervaning from happening outside of the timer
3821 weathervane->reset();
3822 return 0.0;
3825 const bool is_takeoff = in_vtol_auto() && is_vtol_takeoff(plane.mission.get_current_nav_cmd().id);
3826 float wv_output;
3827 if (weathervane->get_yaw_out(wv_output,
3828 plane.channel_rudder->get_control_in(),
3829 plane.relative_ground_altitude(plane.g.rangefinder_landing),
3830 pos_control->get_roll_cd(),
3831 pos_control->get_pitch_cd(),
3832 is_takeoff,
3833 in_vtol_land_sequence())) {
3834 return constrain_float(wv_output * (1/45.0), -100.0, 100.0) * command_model_pilot.get_rate() * 0.5;
3837 return 0.0;
3841 start guided mode control
3843 void QuadPlane::guided_start(void)
3845 guided_takeoff = false;
3846 setup_target_position();
3847 int32_t from_alt;
3848 int32_t to_alt;
3849 poscontrol_init_approach();
3850 if (plane.current_loc.get_alt_cm(Location::AltFrame::ABSOLUTE,from_alt) && plane.next_WP_loc.get_alt_cm(Location::AltFrame::ABSOLUTE,to_alt)) {
3851 poscontrol.slow_descent = from_alt > to_alt;
3852 } else {
3853 // default back to old method
3854 poscontrol.slow_descent = (plane.current_loc.alt > plane.next_WP_loc.alt);
3859 update guided mode control
3861 void QuadPlane::guided_update(void)
3863 if (plane.control_mode == &plane.mode_guided && guided_takeoff && plane.current_loc.alt < plane.next_WP_loc.alt) {
3864 throttle_wait = false;
3865 set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
3866 takeoff_controller();
3867 } else {
3868 if (guided_takeoff) {
3869 poscontrol.set_state(QPOS_POSITION2);
3871 guided_takeoff = false;
3872 // run VTOL position controller
3873 vtol_position_controller();
3877 void QuadPlane::afs_terminate(void)
3879 if (available()) {
3880 set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN);
3881 motors->output();
3886 return true if we should do guided mode loitering using VTOL motors
3888 bool QuadPlane::guided_mode_enabled(void)
3890 if (!available()) {
3891 return false;
3893 // only use quadplane guided when in AUTO or GUIDED mode
3894 if (plane.control_mode != &plane.mode_guided && plane.control_mode != &plane.mode_auto) {
3895 return false;
3897 if (plane.control_mode == &plane.mode_auto &&
3898 plane.mission.get_current_nav_cmd().id == MAV_CMD_NAV_LOITER_TURNS) {
3899 // loiter turns is a fixed wing only operation
3900 return false;
3902 return guided_mode != 0;
3906 set altitude target to current altitude
3908 void QuadPlane::set_alt_target_current(void)
3910 pos_control->set_pos_target_z_cm(inertial_nav.get_position_z_up_cm());
3913 // user initiated takeoff for guided mode
3914 bool QuadPlane::do_user_takeoff(float takeoff_altitude)
3916 if (plane.control_mode != &plane.mode_guided) {
3917 gcs().send_text(MAV_SEVERITY_INFO, "User Takeoff only in GUIDED mode");
3918 return false;
3920 if (!plane.arming.is_armed_and_safety_off()) {
3921 gcs().send_text(MAV_SEVERITY_INFO, "Must be armed for takeoff");
3922 return false;
3924 if (is_flying()) {
3925 gcs().send_text(MAV_SEVERITY_INFO, "Already flying - no takeoff");
3926 return false;
3928 plane.auto_state.vtol_loiter = true;
3929 plane.prev_WP_loc = plane.current_loc;
3930 plane.next_WP_loc = plane.current_loc;
3931 plane.next_WP_loc.alt += takeoff_altitude*100;
3932 set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
3933 guided_start();
3934 guided_takeoff = true;
3935 guided_wait_takeoff = false;
3936 if (!option_is_set(QuadPlane::OPTION::DISABLE_GROUND_EFFECT_COMP)) {
3937 ahrs.set_takeoff_expected(true);
3939 return true;
3942 // return true if the wp_nav controller is being updated
3943 bool QuadPlane::using_wp_nav(void) const
3945 if (plane.control_mode == &plane.mode_qloiter || plane.control_mode == &plane.mode_qland) {
3946 return true;
3948 return false;
3952 return mav_type for heartbeat
3954 MAV_TYPE QuadPlane::get_mav_type(void) const
3956 if (mav_type.get() == 0) {
3957 return MAV_TYPE_FIXED_WING;
3959 return MAV_TYPE(mav_type.get());
3963 return true if current mission item is a vtol takeoff
3965 bool QuadPlane::is_vtol_takeoff(uint16_t id) const
3967 if (id == MAV_CMD_NAV_VTOL_TAKEOFF) {
3968 return true;
3970 if (id == MAV_CMD_NAV_TAKEOFF && available() && !option_is_set(QuadPlane::OPTION::ALLOW_FW_TAKEOFF)) {
3971 // treat fixed wing takeoff as VTOL takeoff
3972 return true;
3974 return false;
3978 return true if current mission item is a vtol land
3980 bool QuadPlane::is_vtol_land(uint16_t id) const
3982 if (id == MAV_CMD_NAV_VTOL_LAND || id == MAV_CMD_NAV_PAYLOAD_PLACE) {
3983 if (landing_with_fixed_wing_spiral_approach()) {
3984 return plane.vtol_approach_s.approach_stage == Plane::Landing_ApproachStage::VTOL_LANDING;
3985 } else {
3986 return true;
3989 if (id == MAV_CMD_NAV_LAND && available() && !option_is_set(QuadPlane::OPTION::ALLOW_FW_LAND)) {
3990 // treat fixed wing land as VTOL land
3991 return true;
3993 return false;
3997 return true if we are in a transition to fwd flight from hover
3999 bool QuadPlane::in_transition(void) const
4001 return available() && transition->active();
4005 calculate current stopping distance for a quadplane in fixed wing flight
4007 float QuadPlane::stopping_distance(float ground_speed_squared) const
4009 // use v^2/(2*accel). This is only quite approximate as the drag
4010 // varies with pitch, but it gives something for the user to
4011 // control the transition distance in a reasonable way
4012 return ground_speed_squared / (2 * transition_decel);
4016 calculate acceleration needed to stop in the given distance given current speed
4018 float QuadPlane::accel_needed(float stop_distance, float ground_speed_squared) const
4020 return ground_speed_squared / (2 * MAX(1,stop_distance));
4024 calculate current stopping distance for a quadplane in fixed wing flight
4026 float QuadPlane::stopping_distance(void)
4028 return stopping_distance(plane.ahrs.groundspeed_vector().length_squared());
4032 distance below which we don't do approach, based on stopping
4033 distance for cruise speed
4035 float QuadPlane::transition_threshold(void)
4037 // 1.5 times stopping distance for cruise speed
4038 return 1.5 * stopping_distance(sq(plane.aparm.airspeed_cruise));
4041 #define LAND_CHECK_ANGLE_ERROR_DEG 30.0f // maximum angle error to be considered landing
4042 #define LAND_CHECK_LARGE_ANGLE_CD 1500.0f // maximum angle target to be considered landing
4043 #define LAND_CHECK_ACCEL_MOVING 3.0f // maximum acceleration after subtracting gravity
4045 void QuadPlane::update_throttle_mix(void)
4047 // update filtered acceleration
4048 Vector3f accel_ef = ahrs.get_accel_ef();
4049 accel_ef.z += GRAVITY_MSS;
4050 throttle_mix_accel_ef_filter.apply(accel_ef, plane.scheduler.get_loop_period_s());
4052 // transition will directly manage the mix
4053 if (!transition->allow_update_throttle_mix()) {
4054 return;
4057 // if disarmed or landed prioritise throttle
4058 if (!motors->armed()) {
4059 attitude_control->set_throttle_mix_min();
4060 return;
4063 if (plane.control_mode->is_vtol_man_throttle()) {
4064 // manual throttle
4065 if (!is_positive(get_throttle_input()) && !air_mode_active()) {
4066 attitude_control->set_throttle_mix_min();
4067 } else {
4068 attitude_control->set_throttle_mix_man();
4070 } else {
4071 // autopilot controlled throttle
4073 // check for aggressive flight requests - requested roll or pitch angle below 15 degrees
4074 const Vector3f angle_target = attitude_control->get_att_target_euler_cd();
4075 bool large_angle_request = angle_target.xy().length() > LAND_CHECK_LARGE_ANGLE_CD;
4077 // check for large external disturbance - angle error over 30 degrees
4078 const float angle_error = attitude_control->get_att_error_angle_deg();
4079 bool large_angle_error = (angle_error > LAND_CHECK_ANGLE_ERROR_DEG);
4081 // check for large acceleration - falling or high turbulence
4082 bool accel_moving = (throttle_mix_accel_ef_filter.get().length() > LAND_CHECK_ACCEL_MOVING);
4084 // check for requested descent
4085 bool descent_not_demanded = pos_control->get_vel_desired_cms().z >= 0.0f;
4087 bool use_mix_max = large_angle_request || large_angle_error || accel_moving || descent_not_demanded;
4090 special case for auto landing, we want a high degree of
4091 attitude control until LAND_FINAL
4093 if (in_vtol_land_sequence()) {
4094 use_mix_max = !in_vtol_land_final();
4097 if (use_mix_max) {
4098 attitude_control->set_throttle_mix_max(1.0);
4099 } else {
4100 attitude_control->set_throttle_mix_min();
4106 see if we are in the approach phase of a VTOL landing
4108 bool QuadPlane::in_vtol_land_approach(void) const
4110 if (plane.control_mode == &plane.mode_qrtl &&
4111 poscontrol.get_state() <= QPOS_POSITION2) {
4112 return true;
4114 if (in_vtol_auto()) {
4115 if (is_vtol_land(plane.mission.get_current_nav_cmd().id) &&
4116 (poscontrol.get_state() == QPOS_APPROACH ||
4117 poscontrol.get_state() == QPOS_AIRBRAKE ||
4118 poscontrol.get_state() == QPOS_POSITION1 ||
4119 poscontrol.get_state() == QPOS_POSITION2)) {
4120 return true;
4123 return false;
4127 see if we are in the descent phase of a VTOL landing
4129 bool QuadPlane::in_vtol_land_descent(void) const
4131 const auto state = poscontrol.get_state();
4132 if (plane.control_mode == &plane.mode_qrtl &&
4133 (state == QPOS_LAND_DESCEND || state == QPOS_LAND_FINAL || state == QPOS_LAND_ABORT)) {
4134 return true;
4136 if (in_vtol_auto() && is_vtol_land(plane.mission.get_current_nav_cmd().id) &&
4137 (state == QPOS_LAND_DESCEND || state == QPOS_LAND_FINAL || state == QPOS_LAND_ABORT)) {
4138 return true;
4140 return false;
4144 see if we are in the final phase of a VTOL landing
4146 bool QuadPlane::in_vtol_land_final(void) const
4148 return in_vtol_land_descent() && poscontrol.get_state() == QPOS_LAND_FINAL;
4152 see if we are in any of the phases of a VTOL landing
4154 bool QuadPlane::in_vtol_land_sequence(void) const
4156 return plane.control_mode == &plane.mode_qrtl || in_vtol_land_approach() || in_vtol_land_descent() || in_vtol_land_final();
4160 see if we are in the VTOL position control phase of a landing
4162 bool QuadPlane::in_vtol_land_poscontrol(void) const
4164 if (in_vtol_auto() && is_vtol_land(plane.mission.get_current_nav_cmd().id) &&
4165 poscontrol.get_state() >= QPOS_POSITION1) {
4166 return true;
4168 return false;
4172 see if we are in the airbrake phase of a VTOL landing
4174 bool QuadPlane::in_vtol_airbrake(void) const
4176 if (plane.control_mode == &plane.mode_qrtl &&
4177 poscontrol.get_state() == QPOS_AIRBRAKE) {
4178 return true;
4180 if (plane.control_mode == &plane.mode_auto &&
4181 is_vtol_land(plane.mission.get_current_nav_cmd().id) &&
4182 poscontrol.get_state() == QPOS_AIRBRAKE) {
4183 return true;
4185 return false;
4188 // return true if we should show VTOL view
4189 bool QuadPlane::show_vtol_view() const
4191 return available() && transition->show_vtol_view();
4194 // return true if we should show VTOL view
4195 bool SLT_Transition::show_vtol_view() const
4198 return quadplane.in_vtol_mode();
4202 return the PILOT_VELZ_MAX_DN value if non zero, otherwise returns the PILOT_VELZ_MAX value.
4203 return is in cm/s
4205 uint16_t QuadPlane::get_pilot_velocity_z_max_dn() const
4207 if (is_zero(pilot_speed_z_max_dn)) {
4208 return abs(pilot_speed_z_max_up*100);
4210 return abs(pilot_speed_z_max_dn*100);
4214 should we use the fixed wing attitude controllers for roll/pitch control
4216 bool QuadPlane::use_fw_attitude_controllers(void) const
4218 if (available() &&
4219 motors->armed() &&
4220 motors->get_desired_spool_state() >= AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED &&
4221 in_vtol_mode() &&
4222 !tailsitter.enabled() &&
4223 poscontrol.get_state() != QPOS_AIRBRAKE) {
4224 // we want the desired rates for fixed wing slaved to the
4225 // multicopter rates
4226 return false;
4228 return true;
4232 calculate our closing velocity vector on the landing point, taking
4233 into account target velocity
4235 Vector2f QuadPlane::landing_closing_velocity()
4237 Vector2f landing_velocity;
4238 if (AP_HAL::millis() - poscontrol.last_velocity_match_ms < 1000) {
4239 landing_velocity = poscontrol.velocity_match;
4241 return ahrs.groundspeed_vector() - landing_velocity;
4245 calculate our desired closing velocity vector on the landing point.
4247 Vector2f QuadPlane::landing_desired_closing_velocity()
4249 if (poscontrol.get_state() >= QPOS_LAND_DESCEND) {
4250 return Vector2f(0,0);
4252 const Vector2f diff_wp = plane.current_loc.get_distance_NE(plane.next_WP_loc);
4253 float dist = diff_wp.length();
4254 if (dist < 1) {
4255 return Vector2f(0,0);
4258 // base target speed based on sqrt of distance
4259 float target_speed = safe_sqrt(2*transition_decel*dist);
4261 // don't let the target speed go above landing approach speed
4262 const float eas2tas = plane.ahrs.get_EAS2TAS();
4263 float land_speed = plane.aparm.airspeed_cruise;
4264 float tecs_land_airspeed = plane.TECS_controller.get_land_airspeed();
4265 if (is_positive(tecs_land_airspeed)) {
4266 land_speed = tecs_land_airspeed;
4267 } else {
4268 // use half way between min airspeed and cruise if
4269 // TECS_LAND_AIRSPEED not set
4270 land_speed = 0.5*(land_speed+plane.aparm.airspeed_min);
4272 target_speed = MIN(target_speed, eas2tas * land_speed);
4274 Vector2f target_speed_xy = diff_wp.normalized() * target_speed;
4276 return target_speed_xy;
4280 get target airspeed for landing, for use by TECS
4282 float QuadPlane::get_land_airspeed(void)
4284 const auto qstate = poscontrol.get_state();
4285 if (qstate == QPOS_APPROACH ||
4286 plane.control_mode == &plane.mode_rtl) {
4287 const float cruise_speed = plane.aparm.airspeed_cruise;
4288 float approach_speed = cruise_speed;
4289 float tecs_land_airspeed = plane.TECS_controller.get_land_airspeed();
4290 if (is_positive(tecs_land_airspeed)) {
4291 approach_speed = tecs_land_airspeed;
4292 } else {
4293 if (qstate == QPOS_APPROACH) {
4294 // default to half way between min airspeed and cruise
4295 // airspeed when on the approach
4296 approach_speed = 0.5*(cruise_speed+plane.aparm.airspeed_min);
4297 } else {
4298 // otherwise cruise
4299 approach_speed = cruise_speed;
4302 const float time_to_pos1 = (plane.auto_state.wp_distance - stopping_distance(sq(approach_speed))) / MAX(approach_speed, 5);
4304 slow down to landing approach speed as we get closer to landing
4306 approach_speed = linear_interpolate(approach_speed, cruise_speed,
4307 time_to_pos1,
4308 20, 60);
4309 return approach_speed;
4312 if (qstate == QPOS_AIRBRAKE) {
4313 // during airbraking ask TECS to slow us to stall speed
4314 return plane.aparm.airspeed_min;
4317 // calculate speed based on landing desired velocity
4318 Vector2f vel = landing_desired_closing_velocity();
4319 const Vector2f wind = plane.ahrs.wind_estimate().xy();
4320 const float eas2tas = plane.ahrs.get_EAS2TAS();
4321 vel -= wind;
4322 vel /= eas2tas;
4323 return vel.length();
4326 void QuadPlane::set_desired_spool_state(AP_Motors::DesiredSpoolState state)
4328 if (motors->get_desired_spool_state() != state) {
4329 if (state == AP_Motors::DesiredSpoolState::SHUT_DOWN) {
4330 // also request zero throttle, so we avoid the slow ramp down
4331 motors->set_roll(0);
4332 motors->set_pitch(0);
4333 motors->set_yaw(0);
4334 motors->set_throttle(0);
4336 motors->set_desired_spool_state(state);
4340 bool QuadPlane::air_mode_active() const
4342 if ((air_mode == AirMode::ON) || ((air_mode == AirMode::ASSISTED_FLIGHT_ONLY) && assisted_flight)) {
4343 return true;
4345 return false;
4349 return scaling factor for tilting rotors in forward flight throttle
4350 we want to scale back tilt angle for roll/pitch by throttle in forward flight
4352 float QuadPlane::FW_vector_throttle_scaling()
4354 const float throttle = SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) * 0.01;
4355 // scale relative to a fixed 0.5 mid throttle so that changes in TRIM_THROTTLE in missions don't change
4356 // the scaling of tilt
4357 const float mid_throttle = 0.5;
4358 return mid_throttle / constrain_float(throttle, 0.1, 1.0);
4361 QuadPlane *QuadPlane::_singleton = nullptr;
4363 bool SLT_Transition::set_FW_roll_limit(int32_t& roll_limit_cd)
4365 if (quadplane.assisted_flight && (transition_state == TRANSITION_AIRSPEED_WAIT || transition_state == TRANSITION_TIMER) &&
4366 quadplane.option_is_set(QuadPlane::OPTION::LEVEL_TRANSITION)) {
4367 // the user wants transitions to be kept level to within LEVEL_ROLL_LIMIT
4368 roll_limit_cd = MIN(roll_limit_cd, plane.g.level_roll_limit*100);
4369 return true;
4371 return false;
4374 bool SLT_Transition::allow_update_throttle_mix() const
4376 // transition is directly managing throttle mix in these cases
4377 return !(quadplane.assisted_flight && (transition_state == TRANSITION_AIRSPEED_WAIT || transition_state == TRANSITION_TIMER));
4380 bool SLT_Transition::active() const
4382 return quadplane.assisted_flight && ((transition_state == TRANSITION_AIRSPEED_WAIT) || (transition_state == TRANSITION_TIMER));
4386 limit VTOL roll/pitch in POSITION1, POSITION2 and waypoint controller. This serves three roles:
4387 1) an expanding envelope limit on pitch to prevent sudden pitch at the start of a back transition
4389 2) limiting roll and pitch down to the Q_ANGLE_MAX, as the accel limits may push us beyond that for pitch up.
4390 This is needed as the position controller doesn't have separate limits for pitch and roll
4392 3) preventing us pitching up a lot when our airspeed may be low
4393 enough that the real airspeed may be negative, which would result
4394 in reversed control surfaces
4396 bool SLT_Transition::set_VTOL_roll_pitch_limit(int32_t& roll_cd, int32_t& pitch_cd)
4398 bool ret = false;
4399 const int16_t angle_max = quadplane.aparm.angle_max;
4402 we always limit roll to Q_ANGLE_MAX
4404 int32_t new_roll_cd = constrain_int32(roll_cd, -angle_max, angle_max);
4405 if (new_roll_cd != roll_cd) {
4406 roll_cd = new_roll_cd;
4407 ret = true;
4411 always limit pitch down to Q_ANGLE_MAX. We need to do this as
4412 the position controller accel limits may exceed this limit
4414 if (pitch_cd < -angle_max) {
4415 pitch_cd = -angle_max;
4416 ret = true;
4420 prevent trying to fly backwards (negative airspeed) at high
4421 pitch angles, which can result in a high degree of instability
4422 in SLT aircraft. This can happen with a tailwind in a back
4423 transition, where the position controller (which is unaware of
4424 airspeed) demands high pitch to hit the desired landing point
4426 float airspeed;
4427 if (pitch_cd > angle_max &&
4428 plane.ahrs.airspeed_estimate(airspeed) && airspeed < 0.5 * plane.aparm.airspeed_min) {
4429 const float max_limit_cd = linear_interpolate(angle_max, 4500,
4430 airspeed,
4431 0, 0.5 * plane.aparm.airspeed_min);
4432 if (pitch_cd > max_limit_cd) {
4433 pitch_cd = max_limit_cd;
4434 ret = true;
4438 if (quadplane.back_trans_pitch_limit_ms <= 0) {
4439 // time based pitch envelope disabled
4440 return ret;
4443 const uint32_t limit_time_ms = quadplane.back_trans_pitch_limit_ms;
4445 const uint32_t dt = AP_HAL::millis() - last_fw_mode_ms;
4446 if (last_fw_mode_ms == 0 || dt > limit_time_ms) {
4447 // we are beyond the time limit, don't apply envelope
4448 last_fw_mode_ms = 0;
4449 return ret;
4452 // we limit pitch during initial transition
4453 const float max_limit_cd = linear_interpolate(MAX(last_fw_nav_pitch_cd,0), MIN(angle_max,plane.aparm.pitch_limit_max*100),
4455 0, limit_time_ms);
4457 if (pitch_cd > max_limit_cd) {
4458 pitch_cd = max_limit_cd;
4459 return true;
4463 limit the pitch down with an expanding envelope. This
4464 prevents the velocity controller demanding nose down during
4465 the initial slowdown if the target velocity curve is higher
4466 than the actual velocity curve (for a high drag
4467 aircraft). Nose down will cause a lot of downforce on the
4468 wings which will draw a lot of current and also cause the
4469 aircraft to lose altitude rapidly.pitch limit varies also with speed
4470 to prevent inability to progress to position if moving from a loiter
4471 to landing
4473 const float min_limit_cd = linear_interpolate(MIN(last_fw_nav_pitch_cd,0), MAX(-angle_max,plane.aparm.pitch_limit_min*100),
4475 0, limit_time_ms);
4477 if (plane.nav_pitch_cd < min_limit_cd) {
4478 plane.nav_pitch_cd = min_limit_cd;
4479 return true;
4482 return ret;
4486 remember last fixed wing pitch for pitch envelope in back transition
4488 void SLT_Transition::set_last_fw_pitch()
4490 last_fw_mode_ms = AP_HAL::millis();
4491 last_fw_nav_pitch_cd = plane.nav_pitch_cd;
4494 void SLT_Transition::force_transition_complete() {
4495 transition_state = TRANSITION_DONE;
4496 in_forced_transition = false;
4497 transition_start_ms = 0;
4498 transition_low_airspeed_ms = 0;
4499 set_last_fw_pitch();
4501 // Keep assistance reset while not checking
4502 quadplane.assist.reset();
4505 MAV_VTOL_STATE SLT_Transition::get_mav_vtol_state() const
4507 if (quadplane.in_vtol_mode()) {
4508 QuadPlane::position_control_state state = quadplane.poscontrol.get_state();
4509 if ((state == QuadPlane::position_control_state::QPOS_AIRBRAKE) || (state == QuadPlane::position_control_state::QPOS_POSITION1)) {
4510 return MAV_VTOL_STATE_TRANSITION_TO_MC;
4512 return MAV_VTOL_STATE_MC;
4515 switch (transition_state) {
4516 case TRANSITION_AIRSPEED_WAIT:
4517 case TRANSITION_TIMER:
4518 // we enter this state during assisted flight, not just
4519 // during a forward transition.
4520 return MAV_VTOL_STATE_TRANSITION_TO_FW;
4522 case TRANSITION_DONE:
4523 return MAV_VTOL_STATE_FW;
4526 return MAV_VTOL_STATE_UNDEFINED;
4529 // Set FW roll and pitch limits and keep TECS informed
4530 void SLT_Transition::set_FW_roll_pitch(int32_t& nav_pitch_cd, int32_t& nav_roll_cd)
4532 if (quadplane.in_vtol_mode() || quadplane.in_vtol_airbrake()) {
4533 // not in FW flight
4534 return;
4537 if (transition_state == TRANSITION_DONE) {
4538 // transition complete, nothing to do
4539 return;
4542 if (!plane.control_mode->does_auto_throttle()) {
4543 // don't limit pitch when in manually controlled modes like FBWA, ACRO
4544 return;
4547 float max_pitch;
4548 if (transition_state < TRANSITION_TIMER) {
4549 if (plane.ahrs.groundspeed() < 3.0) {
4550 // until we have some ground speed limit to zero pitch
4551 max_pitch = 0.0;
4552 } else {
4553 max_pitch = quadplane.transition_pitch_max;
4555 } else {
4556 max_pitch = (quadplane.transition_pitch_max+1.0)*2.0;
4559 // set a single loop pitch limit in TECS
4560 plane.TECS_controller.set_pitch_max_limit(max_pitch);
4562 // ensure pitch is constrained to limit
4563 nav_pitch_cd = constrain_int32(nav_pitch_cd, -max_pitch*100.0, max_pitch*100.0);
4567 see if we are in a VTOL takeoff
4569 bool QuadPlane::in_vtol_takeoff(void) const
4571 if (in_vtol_auto() && is_vtol_takeoff(plane.mission.get_current_nav_cmd().id)) {
4572 return true;
4574 return false;
4577 // called when we change mode (for any mode, not just Q modes)
4578 void QuadPlane::mode_enter(void)
4580 if (available()) {
4581 pos_control->set_lean_angle_max_cd(0);
4583 poscontrol.xy_correction.zero();
4584 poscontrol.velocity_match.zero();
4585 poscontrol.last_velocity_match_ms = 0;
4586 poscontrol.set_state(QuadPlane::QPOS_NONE);
4588 // clear guided takeoff wait on any mode change, but remember the
4589 // state for special behaviour
4590 guided_wait_takeoff_on_mode_enter = guided_wait_takeoff;
4591 guided_wait_takeoff = false;
4593 q_fwd_throttle = 0.0f;
4594 q_fwd_pitch_lim_cd = 100.0f * q_fwd_pitch_lim;
4597 // Set attitude control yaw rate time constant to pilot input command model value
4598 void QuadPlane::set_pilot_yaw_rate_time_constant()
4600 attitude_control->set_yaw_rate_tc(command_model_pilot.get_rate_tc());
4603 // Disable attitude control yaw rate time constant
4604 void QuadPlane::disable_yaw_rate_time_constant()
4606 attitude_control->set_yaw_rate_tc(0.0);
4609 // Check if servo auto trim is allowed, only if countrol surfaces are fully in use
4610 bool QuadPlane::allow_servo_auto_trim()
4612 if (!available()) {
4613 // Quadplane disabled, auto trim always allowed
4614 return true;
4616 if (in_vtol_mode()) {
4617 // VTOL motors active in VTOL modes
4618 return false;
4620 if (!in_assisted_flight()) {
4621 // In forward flight and VTOL motors not active
4622 return true;
4624 if (tailsitter.enabled() && option_is_set(QuadPlane::OPTION::TAILSIT_Q_ASSIST_MOTORS_ONLY)) {
4625 // Tailsitter in forward flight, motors providing active stabalisation with motors only option
4626 // Control surfaces are running as normal with I term active, motor I term is zeroed
4627 return true;
4629 // In forward flight with active VTOL motors
4630 return false;
4633 bool QuadPlane::landing_with_fixed_wing_spiral_approach(void) const
4635 const AP_Mission::Mission_Command cmd = plane.mission.get_current_nav_cmd();
4637 if (cmd.id == MAV_CMD_NAV_PAYLOAD_PLACE &&
4638 option_is_set(QuadPlane::OPTION::MISSION_LAND_FW_APPROACH)) {
4639 return true;
4642 return ((cmd.id == MAV_CMD_NAV_VTOL_LAND) &&
4643 (option_is_set(QuadPlane::OPTION::MISSION_LAND_FW_APPROACH) ||
4644 cmd.p1 == NAV_VTOL_LAND_OPTIONS_FW_SPIRAL_APPROACH));
4648 setup scaling of roll and pitch angle P gains to match fixed wing gains
4650 we setup the angle P gain to match fixed wing at high speed (above
4651 AIRSPEED_MIN) where fixed wing surfaces are presumed to
4652 dominate. At lower speeds we use the multicopter angle P gains.
4654 void QuadPlane::setup_rp_fw_angle_gains(void)
4656 const float mc_angR = attitude_control->get_angle_roll_p().kP();
4657 const float mc_angP = attitude_control->get_angle_pitch_p().kP();
4658 const float fw_angR = 1.0/plane.rollController.tau();
4659 const float fw_angP = 1.0/plane.pitchController.tau();
4661 if (!is_positive(mc_angR) || !is_positive(mc_angP)) {
4662 // bad configuration, don't scale
4663 return;
4666 float aspeed;
4667 if (!ahrs.airspeed_estimate(aspeed)) {
4668 // can't get airspeed, no scaling of VTOL angle gains
4669 return;
4672 const float low_airspeed = 3.0;
4673 if (aspeed <= low_airspeed || plane.aparm.airspeed_min <= low_airspeed) {
4674 // no scaling
4675 return;
4678 const float angR_scale = linear_interpolate(mc_angR, fw_angR,
4679 aspeed,
4680 low_airspeed, plane.aparm.airspeed_min) / mc_angR;
4681 const float angP_scale = linear_interpolate(mc_angP, fw_angP,
4682 aspeed,
4683 low_airspeed, plane.aparm.airspeed_min) / mc_angP;
4684 const Vector3f gain_scale{angR_scale, angP_scale, 1.0};
4685 attitude_control->set_angle_P_scale(gain_scale);
4689 abort landing, used by scripting for payload place and ship landing abort
4690 will return false if not in a landing descent
4692 bool QuadPlane::abort_landing(void)
4694 if (poscontrol.get_state() == QPOS_LAND_ABORT ||
4695 !(plane.control_mode == &plane.mode_auto)) {
4696 // already aborted or not in AUTO?
4697 return false;
4700 // special case for payload place with full landing
4701 const bool payload_place_landed =
4702 plane.in_auto_mission_id(MAV_CMD_NAV_PAYLOAD_PLACE) &&
4703 poscontrol.get_state() == QPOS_LAND_COMPLETE;
4705 if (!payload_place_landed && !in_vtol_land_descent()) {
4706 return false;
4708 poscontrol.set_state(QuadPlane::QPOS_LAND_ABORT);
4709 return true;
4712 // Should we allow stick mixing from the pilot
4713 bool QuadPlane::allow_stick_mixing() const
4715 if (!available()) {
4716 // Quadplane not enabled
4717 return true;
4719 // Ask transition logic
4720 return transition->allow_stick_mixing();
4724 return true if we should disable TECS in the current flight state
4725 this ensures that TECS resets when we change height in a VTOL mode
4727 bool QuadPlane::should_disable_TECS() const
4729 if (in_vtol_land_descent()) {
4730 return true;
4732 if (plane.control_mode == &plane.mode_guided &&
4733 plane.auto_state.vtol_loiter) {
4734 return true;
4736 return false;
4739 // Get pilot throttle input with deadzone, this will return 50% throttle in failsafe!
4740 // This is a re-implmentation of Plane::get_throttle_input
4741 // Ignoring the no_deadzone case means we don't need to check for valid RC
4742 // This is handled by Plane::control_failsafe setting of control in
4743 float QuadPlane::get_throttle_input() const
4745 float ret = plane.channel_throttle->get_control_in();
4746 if (plane.reversed_throttle) {
4747 // RC option for reverse throttle has been set
4748 ret = -ret;
4750 return ret;
4753 // return true if forward throttle from forward_throttle_pct() should be used
4754 bool QuadPlane::allow_forward_throttle_in_vtol_mode() const
4756 return in_vtol_mode() && motors->armed() && (motors->get_desired_spool_state() != AP_Motors::DesiredSpoolState::SHUT_DOWN);
4759 #endif // HAL_QUADPLANE_ENABLED