Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
ardupilot
GitHub Repository: ardupilot/ardupilot
Path: blob/master/ArduPlane/Attitude.cpp
2981 views
1
#include "Plane.h"
2
3
/*
4
calculate speed scaling number for control surfaces. This is applied
5
to PIDs to change the scaling of the PID with speed. At high speed
6
we move the surfaces less, and at low speeds we move them more.
7
*/
8
float Plane::calc_speed_scaler(void)
9
{
10
float aspeed, speed_scaler;
11
if (ahrs.airspeed_estimate(aspeed)) {
12
if (aspeed > auto_state.highest_airspeed && arming.is_armed_and_safety_off()) {
13
auto_state.highest_airspeed = aspeed;
14
}
15
// ensure we have scaling over the full configured airspeed
16
const float airspeed_min = MAX(aparm.airspeed_min, MIN_AIRSPEED_MIN);
17
const float scale_min = MIN(0.5, g.scaling_speed / (2.0 * aparm.airspeed_max));
18
const float scale_max = MAX(2.0, g.scaling_speed / (0.7 * airspeed_min));
19
if (aspeed > 0.0001f) {
20
speed_scaler = g.scaling_speed / aspeed;
21
} else {
22
speed_scaler = scale_max;
23
}
24
speed_scaler = constrain_float(speed_scaler, scale_min, scale_max);
25
26
#if HAL_QUADPLANE_ENABLED
27
if ((quadplane.in_vtol_mode() || quadplane.in_assisted_flight()) && arming.is_armed_and_safety_off()) {
28
// when in VTOL modes limit surface movement at low speed to prevent instability
29
float threshold = airspeed_min * 0.5;
30
if (aspeed < threshold) {
31
float new_scaler = linear_interpolate(0.001, g.scaling_speed / threshold, aspeed, 0, threshold);
32
speed_scaler = MIN(speed_scaler, new_scaler);
33
34
// we also decay the integrator to prevent an integrator from before
35
// we were at low speed persistent at high speed
36
rollController.decay_I();
37
pitchController.decay_I();
38
yawController.decay_I();
39
}
40
}
41
#endif
42
} else if (arming.is_armed_and_safety_off()) {
43
// scale assumed surface movement using throttle output
44
float throttle_out = MAX(SRV_Channels::get_output_scaled(SRV_Channel::k_throttle), 1);
45
// we use a fixed value here as changing the trim throttle
46
// value is often done at runtime - and changing that
47
// shouldn't change the speed scaler here (it will change the
48
// effective PID values)
49
speed_scaler = sqrtf(AP_PLANE_TRIM_THROTTLE_DEFAULT / throttle_out);
50
// This case is constrained tighter as we don't have real speed info
51
speed_scaler = constrain_float(speed_scaler, 0.6f, 1.67f);
52
} else {
53
// no speed estimate and not armed, use a unit scaling
54
speed_scaler = 1;
55
}
56
if (!plane.ahrs.using_airspeed_sensor() &&
57
(plane.flight_option_enabled(FlightOptions::SURPRESS_TKOFF_SCALING)) &&
58
(plane.flight_stage == AP_FixedWing::FlightStage::TAKEOFF)) { //scaling is suppressed during climb phase of automatic takeoffs with no airspeed sensor being used due to problems with inaccurate airspeed estimates
59
return MIN(speed_scaler, 1.0f) ;
60
}
61
return speed_scaler;
62
}
63
64
/*
65
return true if the current settings and mode should allow for stick mixing
66
*/
67
bool Plane::stick_mixing_enabled(void)
68
{
69
if (!rc().has_valid_input()) {
70
// never stick mix without valid RC
71
return false;
72
}
73
#if AP_FENCE_ENABLED
74
const bool stickmixing = fence_stickmixing();
75
#else
76
const bool stickmixing = true;
77
#endif
78
#if HAL_QUADPLANE_ENABLED
79
if (control_mode == &mode_qrtl &&
80
quadplane.poscontrol.get_state() >= QuadPlane::QPOS_POSITION1) {
81
// user may be repositioning
82
return false;
83
}
84
if (quadplane.in_vtol_land_poscontrol()) {
85
// user may be repositioning
86
return false;
87
}
88
#endif
89
if (control_mode->does_auto_throttle() && plane.control_mode->does_auto_navigation()) {
90
// we're in an auto mode. Check the stick mixing flag
91
if (g.stick_mixing != StickMixing::NONE &&
92
g.stick_mixing != StickMixing::VTOL_YAW &&
93
stickmixing) {
94
return true;
95
} else {
96
return false;
97
}
98
}
99
100
if (failsafe.rc_failsafe && g.fs_action_short == FS_ACTION_SHORT_FBWA) {
101
// don't do stick mixing in FBWA glide mode
102
return false;
103
}
104
105
// non-auto mode. Always do stick mixing
106
return true;
107
}
108
109
110
/*
111
this is the main roll stabilization function. It takes the
112
previously set nav_roll calculates roll servo_out to try to
113
stabilize the plane at the given roll
114
*/
115
void Plane::stabilize_roll()
116
{
117
if (fly_inverted()) {
118
// we want to fly upside down. We need to cope with wrap of
119
// the roll_sensor interfering with wrap of nav_roll, which
120
// would really confuse the PID code. The easiest way to
121
// handle this is to ensure both go in the same direction from
122
// zero
123
nav_roll_cd += 18000;
124
if (ahrs.roll_sensor < 0) nav_roll_cd -= 36000;
125
}
126
127
const float roll_out = stabilize_roll_get_roll_out();
128
SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, roll_out);
129
}
130
131
float Plane::stabilize_roll_get_roll_out()
132
{
133
const float speed_scaler = get_speed_scaler();
134
#if HAL_QUADPLANE_ENABLED
135
if (!quadplane.use_fw_attitude_controllers()) {
136
// use the VTOL rate for control, to ensure consistency
137
const auto &pid_info = quadplane.attitude_control->get_rate_roll_pid().get_pid_info();
138
139
// scale FF to angle P
140
if (quadplane.option_is_set(QuadPlane::Option::SCALE_FF_ANGLE_P)) {
141
const float mc_angR = quadplane.attitude_control->get_angle_roll_p().kP()
142
* quadplane.attitude_control->get_last_angle_P_scale().x;
143
if (is_positive(mc_angR)) {
144
rollController.set_ff_scale(MIN(1.0, 1.0 / (mc_angR * rollController.tau())));
145
}
146
}
147
148
const float roll_out = rollController.get_rate_out(degrees(pid_info.target), speed_scaler);
149
/* when slaving fixed wing control to VTOL control we need to decay the integrator to prevent
150
opposing integrators balancing between the two controllers
151
*/
152
rollController.decay_I();
153
return roll_out;
154
}
155
#endif
156
157
bool disable_integrator = false;
158
if (control_mode == &mode_stabilize && channel_roll->get_control_in() != 0) {
159
disable_integrator = true;
160
}
161
return rollController.get_servo_out(nav_roll_cd - ahrs.roll_sensor, speed_scaler, disable_integrator,
162
ground_mode && !(plane.flight_option_enabled(FlightOptions::DISABLE_GROUND_PID_SUPPRESSION)));
163
}
164
165
/*
166
this is the main pitch stabilization function. It takes the
167
previously set nav_pitch and calculates servo_out values to try to
168
stabilize the plane at the given attitude.
169
*/
170
void Plane::stabilize_pitch()
171
{
172
int8_t force_elevator = takeoff_tail_hold();
173
if (force_elevator != 0) {
174
// we are holding the tail down during takeoff. Just convert
175
// from a percentage to a -4500..4500 centidegree angle
176
SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, 45*force_elevator);
177
return;
178
}
179
180
const float pitch_out = stabilize_pitch_get_pitch_out();
181
SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, pitch_out);
182
}
183
184
float Plane::stabilize_pitch_get_pitch_out()
185
{
186
const float speed_scaler = get_speed_scaler();
187
#if HAL_QUADPLANE_ENABLED
188
if (!quadplane.use_fw_attitude_controllers()) {
189
// use the VTOL rate for control, to ensure consistency
190
const auto &pid_info = quadplane.attitude_control->get_rate_pitch_pid().get_pid_info();
191
192
// scale FF to angle P
193
if (quadplane.option_is_set(QuadPlane::Option::SCALE_FF_ANGLE_P)) {
194
const float mc_angP = quadplane.attitude_control->get_angle_pitch_p().kP()
195
* quadplane.attitude_control->get_last_angle_P_scale().y;
196
if (is_positive(mc_angP)) {
197
pitchController.set_ff_scale(MIN(1.0, 1.0 / (mc_angP * pitchController.tau())));
198
}
199
}
200
201
const int32_t pitch_out = pitchController.get_rate_out(degrees(pid_info.target), speed_scaler);
202
/* when slaving fixed wing control to VTOL control we need to decay the integrator to prevent
203
opposing integrators balancing between the two controllers
204
*/
205
pitchController.decay_I();
206
return pitch_out;
207
}
208
#endif
209
// if LANDING_FLARE RCx_OPTION switch is set and in FW mode, manual throttle,throttle idle then set pitch to LAND_PITCH_DEG if flight option FORCE_FLARE_ATTITUDE is set
210
#if HAL_QUADPLANE_ENABLED
211
const bool quadplane_in_frwd_transition = quadplane.in_frwd_transition();
212
#else
213
const bool quadplane_in_frwd_transition = false;
214
#endif
215
216
int32_t demanded_pitch = nav_pitch_cd + int32_t(g.pitch_trim * 100.0) + SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) * g.kff_throttle_to_pitch;
217
bool disable_integrator = false;
218
if (control_mode == &mode_stabilize && channel_pitch->get_control_in() != 0) {
219
disable_integrator = true;
220
}
221
/* force landing pitch if:
222
- flare switch high
223
- throttle stick at zero thrust
224
- in fixed wing non auto-throttle mode
225
*/
226
if (!quadplane_in_frwd_transition &&
227
!control_mode->is_vtol_mode() &&
228
!control_mode->does_auto_throttle() &&
229
flare_mode == FlareMode::ENABLED_PITCH_TARGET &&
230
throttle_at_zero()) {
231
demanded_pitch = landing.get_pitch_cd();
232
}
233
234
return pitchController.get_servo_out(demanded_pitch - ahrs.pitch_sensor, speed_scaler, disable_integrator,
235
ground_mode && !(plane.flight_option_enabled(FlightOptions::DISABLE_GROUND_PID_SUPPRESSION)));
236
}
237
238
/*
239
this gives the user control of the aircraft in stabilization modes, only used in Stabilize Mode
240
to be moved to mode_stabilize.cpp in future
241
*/
242
void ModeStabilize::stabilize_stick_mixing_direct()
243
{
244
if (!plane.stick_mixing_enabled()) {
245
return;
246
}
247
#if HAL_QUADPLANE_ENABLED
248
if (!plane.quadplane.allow_stick_mixing()) {
249
return;
250
}
251
#endif
252
float aileron = SRV_Channels::get_output_scaled(SRV_Channel::k_aileron);
253
aileron = plane.channel_roll->stick_mixing(aileron);
254
SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, aileron);
255
256
float elevator = SRV_Channels::get_output_scaled(SRV_Channel::k_elevator);
257
elevator = plane.channel_pitch->stick_mixing(elevator);
258
SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, elevator);
259
}
260
261
/*
262
this gives the user control of the aircraft in stabilization modes
263
using FBW style controls
264
*/
265
void Plane::stabilize_stick_mixing_fbw()
266
{
267
if (!stick_mixing_enabled() ||
268
control_mode == &mode_acro ||
269
control_mode == &mode_fbwa ||
270
control_mode == &mode_autotune ||
271
control_mode == &mode_fbwb ||
272
control_mode == &mode_cruise ||
273
#if HAL_QUADPLANE_ENABLED
274
control_mode == &mode_qstabilize ||
275
control_mode == &mode_qhover ||
276
control_mode == &mode_qloiter ||
277
control_mode == &mode_qland ||
278
control_mode == &mode_qacro ||
279
#if QAUTOTUNE_ENABLED
280
control_mode == &mode_qautotune ||
281
#endif
282
!quadplane.allow_stick_mixing() ||
283
#endif // HAL_QUADPLANE_ENABLED
284
control_mode == &mode_training) {
285
return;
286
}
287
// do FBW style roll stick mixing. We don't treat it linearly however. For
288
// inputs up to half the maximum, we use linear addition to the nav_roll.
289
// Above that it goes non-linear and ends up as 2x the maximum, to ensure
290
// that the user can direct the plane in any direction with stick mixing.
291
float roll_input = channel_roll->norm_input_dz();
292
if (roll_input > 0.5f) {
293
roll_input = (3*roll_input - 1);
294
} else if (roll_input < -0.5f) {
295
roll_input = (3*roll_input + 1);
296
}
297
nav_roll_cd += roll_input * roll_limit_cd;
298
nav_roll_cd = constrain_int32(nav_roll_cd, -roll_limit_cd, roll_limit_cd);
299
300
if (plane.g.stick_mixing == StickMixing::FBW_NO_PITCH) {
301
return;
302
}
303
if ((control_mode == &mode_loiter) && (plane.flight_option_enabled(FlightOptions::ENABLE_LOITER_ALT_CONTROL))) {
304
// loiter is using altitude control based on the pitch stick, don't use it again here
305
return;
306
}
307
308
// do FBW-A style pitch stick mixing. Use the same non-linear approach as
309
// roll, but based on the pitch range rather than the limits to ensure full
310
// stick deflection can override either limit regardless of current
311
// attitude.
312
float pitch_input = channel_pitch->norm_input_dz();
313
if (pitch_input > 0.5f) {
314
pitch_input = (3*pitch_input - 1);
315
} else if (pitch_input < -0.5f) {
316
pitch_input = (3*pitch_input + 1);
317
}
318
if (fly_inverted()) {
319
pitch_input = -pitch_input;
320
}
321
const float pitch_range = aparm.pitch_limit_max.get() - pitch_limit_min;
322
nav_pitch_cd += pitch_input * (pitch_range / 2.0f) * 100;
323
nav_pitch_cd = constrain_int32(nav_pitch_cd, pitch_limit_min*100, aparm.pitch_limit_max.get()*100);
324
}
325
326
327
/*
328
stabilize the yaw axis. There are 3 modes of operation:
329
330
- hold a specific heading with ground steering
331
- rate controlled with ground steering
332
- yaw control for coordinated flight
333
*/
334
void Plane::stabilize_yaw()
335
{
336
bool ground_steering = false;
337
if (landing.is_flaring()) {
338
// in flaring then enable ground steering
339
ground_steering = true;
340
} else {
341
// otherwise use ground steering when no input control and we
342
// are below the GROUND_STEER_ALT
343
ground_steering = (channel_roll->get_control_in() == 0 &&
344
fabsf(relative_altitude) < g.ground_steer_alt);
345
if (!landing.is_ground_steering_allowed()) {
346
// don't use ground steering on landing approach
347
ground_steering = false;
348
}
349
}
350
351
352
/*
353
first calculate steering for a nose or tail
354
wheel. We use "course hold" mode for the rudder when either performing
355
a flare (when the wings are held level) or when in course hold in
356
FBWA mode (when we are below GROUND_STEER_ALT)
357
*/
358
float steering_output = 0.0;
359
if (landing.is_flaring() ||
360
(steer_state.hold_course_cd != -1 && ground_steering)) {
361
steering_output = calc_nav_yaw_course();
362
} else if (ground_steering) {
363
steering_output = calc_nav_yaw_ground();
364
}
365
366
/*
367
now calculate rudder for the rudder
368
*/
369
const float rudder_output = calc_nav_yaw_coordinated();
370
371
if (!ground_steering) {
372
// Not doing ground steering, output rudder on steering channel
373
SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, rudder_output);
374
SRV_Channels::set_output_scaled(SRV_Channel::k_steering, rudder_output);
375
376
} else if (!SRV_Channels::function_assigned(SRV_Channel::k_steering)) {
377
// Ground steering active but no steering output configured, output steering on rudder channel
378
SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, steering_output);
379
SRV_Channels::set_output_scaled(SRV_Channel::k_steering, steering_output);
380
381
} else {
382
// Ground steering with both steering and rudder channels
383
SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, rudder_output);
384
SRV_Channels::set_output_scaled(SRV_Channel::k_steering, steering_output);
385
}
386
387
#if HAL_QUADPLANE_ENABLED
388
// possibly recover from a spin
389
quadplane.assist.output_spin_recovery();
390
#endif
391
}
392
393
/*
394
main stabilization function for all 3 axes
395
*/
396
void Plane::stabilize()
397
{
398
uint32_t now = AP_HAL::millis();
399
#if HAL_QUADPLANE_ENABLED
400
if (quadplane.available()) {
401
quadplane.transition->set_FW_roll_pitch(nav_pitch_cd, nav_roll_cd);
402
}
403
#endif
404
405
if (now - last_stabilize_ms > 2000) {
406
// if we haven't run the rate controllers for 2 seconds then reset
407
control_mode->reset_controllers();
408
}
409
last_stabilize_ms = now;
410
411
if (control_mode == &mode_training ||
412
control_mode == &mode_manual) {
413
plane.control_mode->run();
414
#if AP_SCRIPTING_ENABLED
415
} else if (nav_scripting_active()) {
416
// scripting is in control of roll and pitch rates and throttle
417
const float speed_scaler = get_speed_scaler();
418
const float aileron = rollController.get_rate_out(nav_scripting.roll_rate_dps, speed_scaler);
419
const float elevator = pitchController.get_rate_out(nav_scripting.pitch_rate_dps, speed_scaler);
420
SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, aileron);
421
SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, elevator);
422
float rudder = 0;
423
if (yawController.rate_control_enabled()) {
424
rudder = nav_scripting.rudder_offset_pct * 45;
425
if (nav_scripting.run_yaw_rate_controller) {
426
rudder += yawController.get_rate_out(nav_scripting.yaw_rate_dps, speed_scaler, false);
427
} else {
428
yawController.reset_I();
429
}
430
}
431
SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, rudder);
432
SRV_Channels::set_output_scaled(SRV_Channel::k_steering, rudder);
433
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, plane.nav_scripting.throttle_pct);
434
#endif
435
} else {
436
plane.control_mode->run();
437
}
438
439
/*
440
see if we should zero the attitude controller integrators.
441
*/
442
if (is_zero(get_throttle_input()) &&
443
fabsf(relative_altitude) < 5.0f &&
444
fabsf(barometer.get_climb_rate()) < 0.5f &&
445
ahrs.groundspeed() < 3) {
446
// we are low, with no climb rate, and zero throttle, and very
447
// low ground speed. Zero the attitude controller
448
// integrators. This prevents integrator buildup pre-takeoff.
449
rollController.reset_I();
450
pitchController.reset_I();
451
yawController.reset_I();
452
453
// if moving very slowly also zero the steering integrator
454
if (ahrs.groundspeed() < 1) {
455
steerController.reset_I();
456
}
457
}
458
}
459
460
461
/*
462
* Set the throttle output.
463
* This is called by TECS-enabled flight modes, e.g. AUTO, GUIDED, etc.
464
*/
465
void Plane::calc_throttle()
466
{
467
if (aparm.throttle_cruise <= 1) {
468
// user has asked for zero throttle - this may be done by a
469
// mission which wants to turn off the engine for a parachute
470
// landing
471
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0.0);
472
return;
473
}
474
475
// Read the TECS throttle output and set it to the throttle channel.
476
float commanded_throttle = TECS_controller.get_throttle_demand();
477
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, commanded_throttle);
478
}
479
480
/*****************************************
481
* Calculate desired roll/pitch/yaw angles (in medium freq loop)
482
*****************************************/
483
484
/*
485
calculate yaw control for coordinated flight
486
*/
487
int16_t Plane::calc_nav_yaw_coordinated()
488
{
489
const float speed_scaler = get_speed_scaler();
490
bool disable_integrator = false;
491
int16_t rudder_in = rudder_input();
492
493
int16_t commanded_rudder;
494
bool using_rate_controller = false;
495
496
// Received an external msg that guides yaw in the last 3 seconds?
497
if (control_mode->is_guided_mode() &&
498
plane.guided_state.last_forced_rpy_ms.z > 0 &&
499
millis() - plane.guided_state.last_forced_rpy_ms.z < 3000) {
500
commanded_rudder = plane.guided_state.forced_rpy_cd.z;
501
} else if (autotuning && g.acro_yaw_rate > 0 && yawController.rate_control_enabled()) {
502
// user is doing an AUTOTUNE with yaw rate control
503
const float rudd_expo = rudder_in_expo(true);
504
const float yaw_rate = (rudd_expo/SERVO_MAX) * g.acro_yaw_rate;
505
// add in the coordinated turn yaw rate to make it easier to fly while tuning the yaw rate controller
506
const float coordination_yaw_rate = degrees(GRAVITY_MSS * tanf(cd_to_rad(nav_roll_cd))/MAX(aparm.airspeed_min,smoothed_airspeed));
507
commanded_rudder = yawController.get_rate_out(yaw_rate+coordination_yaw_rate, speed_scaler, false);
508
using_rate_controller = true;
509
} else {
510
if (control_mode == &mode_stabilize && rudder_in != 0) {
511
disable_integrator = true;
512
}
513
514
commanded_rudder = yawController.get_servo_out(speed_scaler, disable_integrator);
515
516
// add in rudder mixing from roll
517
commanded_rudder += SRV_Channels::get_output_scaled(SRV_Channel::k_aileron) * g.kff_rudder_mix;
518
commanded_rudder += rudder_in;
519
}
520
521
if (!using_rate_controller) {
522
/*
523
When not running the yaw rate controller, we need to reset the rate
524
*/
525
yawController.reset_rate_PID();
526
}
527
528
return constrain_int16(commanded_rudder, -4500, 4500);
529
}
530
531
/*
532
calculate yaw control for ground steering with specific course
533
*/
534
int16_t Plane::calc_nav_yaw_course(void)
535
{
536
// holding a specific navigation course on the ground. Used in
537
// auto-takeoff and landing
538
int32_t bearing_error_cd = nav_controller->bearing_error_cd();
539
int16_t steering = steerController.get_steering_out_angle_error(bearing_error_cd);
540
if (stick_mixing_enabled()) {
541
steering = channel_rudder->stick_mixing(steering);
542
}
543
return constrain_int16(steering, -4500, 4500);
544
}
545
546
/*
547
calculate yaw control for ground steering
548
*/
549
int16_t Plane::calc_nav_yaw_ground(void)
550
{
551
if (gps.ground_speed() < 1 &&
552
is_zero(get_throttle_input()) &&
553
flight_stage != AP_FixedWing::FlightStage::TAKEOFF &&
554
flight_stage != AP_FixedWing::FlightStage::ABORT_LANDING) {
555
// manual rudder control while still
556
steer_state.locked_course = false;
557
steer_state.locked_course_err = 0;
558
return rudder_input();
559
}
560
561
// if we haven't been steering for 1s then clear locked course
562
const uint32_t now_ms = AP_HAL::millis();
563
if (now_ms - steer_state.last_steer_ms > 1000) {
564
steer_state.locked_course = false;
565
}
566
steer_state.last_steer_ms = now_ms;
567
568
float steer_rate = (rudder_input()/4500.0f) * g.ground_steer_dps;
569
if (flight_stage == AP_FixedWing::FlightStage::TAKEOFF ||
570
flight_stage == AP_FixedWing::FlightStage::ABORT_LANDING) {
571
steer_rate = 0;
572
}
573
if (!is_zero(steer_rate)) {
574
// pilot is giving rudder input
575
steer_state.locked_course = false;
576
} else if (!steer_state.locked_course) {
577
// pilot has released the rudder stick or we are still - lock the course
578
steer_state.locked_course = true;
579
if (flight_stage != AP_FixedWing::FlightStage::TAKEOFF &&
580
flight_stage != AP_FixedWing::FlightStage::ABORT_LANDING) {
581
steer_state.locked_course_err = 0;
582
}
583
}
584
585
int16_t steering;
586
if (!steer_state.locked_course) {
587
// use a rate controller at the pilot specified rate
588
steering = steerController.get_steering_out_rate(steer_rate);
589
} else {
590
// use a error controller on the summed error
591
int32_t yaw_error_cd = -degrees(steer_state.locked_course_err)*100;
592
steering = steerController.get_steering_out_angle_error(yaw_error_cd);
593
}
594
return constrain_int16(steering, -4500, 4500);
595
}
596
597
598
/*
599
calculate a new nav_pitch_cd from the speed height controller
600
*/
601
void Plane::calc_nav_pitch()
602
{
603
int32_t commanded_pitch = TECS_controller.get_pitch_demand();
604
nav_pitch_cd = constrain_int32(commanded_pitch, pitch_limit_min*100, aparm.pitch_limit_max.get()*100);
605
}
606
607
608
/*
609
calculate a new nav_roll_cd from the navigation controller
610
*/
611
void Plane::calc_nav_roll()
612
{
613
int32_t commanded_roll = nav_controller->nav_roll_cd();
614
nav_roll_cd = constrain_int32(commanded_roll, -roll_limit_cd, roll_limit_cd);
615
update_load_factor();
616
}
617
618
/*
619
adjust nav_pitch_cd for STAB_PITCH_DOWN_CD. This is used to make
620
keeping up good airspeed in FBWA mode easier, as the plane will
621
automatically pitch down a little when at low throttle. It makes
622
FBWA landings without stalling much easier.
623
*/
624
void Plane::adjust_nav_pitch_throttle(void)
625
{
626
int8_t throttle = throttle_percentage();
627
if (throttle >= 0 && throttle < aparm.throttle_cruise && flight_stage != AP_FixedWing::FlightStage::VTOL) {
628
float p = (aparm.throttle_cruise - throttle) / (float)aparm.throttle_cruise;
629
nav_pitch_cd -= g.stab_pitch_down * 100.0f * p;
630
}
631
}
632
633
634
/*
635
calculate a new aerodynamic_load_factor
636
*/
637
void Plane::update_load_factor(void)
638
{
639
float demanded_roll = fabsf(nav_roll_cd*0.01f);
640
if (demanded_roll > 85) {
641
// limit to 85 degrees to prevent numerical errors
642
demanded_roll = 85;
643
}
644
645
// loadFactor = liftForce / gravityForce, where gravityForce = liftForce * cos(roll) on balanced horizontal turn
646
aerodynamic_load_factor = 1.0f / cosf(radians(demanded_roll));
647
648
apply_load_factor_roll_limits();
649
}
650
651
/*
652
limit nav_roll_cd to ensure that the load factor does not take us below the
653
sustainable airspeed
654
*/
655
void Plane::apply_load_factor_roll_limits(void)
656
{
657
#if HAL_QUADPLANE_ENABLED
658
if (quadplane.available() && quadplane.transition->set_FW_roll_limit(roll_limit_cd)) {
659
nav_roll_cd = constrain_int32(nav_roll_cd, -roll_limit_cd, roll_limit_cd);
660
return;
661
}
662
#endif
663
664
if (!aparm.stall_prevention) {
665
// stall prevention is disabled
666
return;
667
}
668
if (fly_inverted()) {
669
// no roll limits when inverted
670
return;
671
}
672
#if HAL_QUADPLANE_ENABLED
673
if (quadplane.tailsitter.active()) {
674
// no limits while hovering
675
return;
676
}
677
#endif
678
679
float stall_airspeed_1g = is_positive(aparm.airspeed_stall)
680
? aparm.airspeed_stall
681
: aparm.airspeed_min;
682
683
float max_load_factor =
684
sq(smoothed_airspeed / MAX(stall_airspeed_1g, 1));
685
686
// allow limiting roll command down to wings-level when necessary if
687
// airspeed is accurate and airspeed stall is set (implying low load factor
688
// overhead)
689
const bool enforce_full_roll_limit =
690
flight_option_enabled(FlightOptions::ENABLE_FULL_AERO_LF_ROLL_LIMITS) &&
691
ahrs.using_airspeed_sensor() && is_positive(aparm.airspeed_stall);
692
693
const float level_roll_limit_deg = g.level_roll_limit;
694
float lf_roll_limit_deg = aparm.roll_limit;
695
if (max_load_factor <= 1) {
696
if (enforce_full_roll_limit) {
697
lf_roll_limit_deg = level_roll_limit_deg;
698
} else {
699
// 25° limit to ensure maneuverability if airspeed estimate is wrong
700
lf_roll_limit_deg = 25;
701
}
702
} else if (max_load_factor < aerodynamic_load_factor) {
703
// the demanded nav_roll would take us past the aerodynamic
704
// load limit. Limit our roll to a bank angle that will keep
705
// the load within what the airframe can handle.
706
lf_roll_limit_deg = degrees(acosf(1.0f / max_load_factor));
707
708
// unless enforcing full limits, allow at least 25 degrees of roll to
709
// ensure the aircraft can be manoeuvered with a bad airspeed estimate.
710
// At 25 degrees the load factor is 1.1 (10%)
711
if (!enforce_full_roll_limit && lf_roll_limit_deg < 25) {
712
lf_roll_limit_deg = 25;
713
}
714
715
// always allow at least the wings level threshold to prevent flyaways
716
if (lf_roll_limit_deg < level_roll_limit_deg) {
717
lf_roll_limit_deg = level_roll_limit_deg;
718
}
719
}
720
721
nav_roll_cd = constrain_int32(nav_roll_cd, -lf_roll_limit_deg * 100, lf_roll_limit_deg * 100);
722
roll_limit_cd = MIN(roll_limit_cd, lf_roll_limit_deg * 100);
723
}
724
725