Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduPlane/Plane.cpp
9316 views
1
/*
2
Lead developer: Andrew Tridgell
3
4
Authors: Doug Weibel, Jose Julio, Jordi Munoz, Jason Short, Randy Mackay, Pat Hickey, John Arne Birkeland, Olivier Adler, Amilcar Lucas, Gregory Fletcher, Paul Riseborough, Brandon Jones, Jon Challinger, Tom Pittenger
5
Thanks to: Chris Anderson, Michael Oborne, Paul Mather, Bill Premerlani, James Cohen, JB from rotorFX, Automatik, Fefenin, Peter Meister, Remzibi, Yury Smirnov, Sandro Benigno, Max Levine, Roberto Navoni, Lorenz Meier, Yury MonZon
6
7
Please contribute your ideas! See https://ardupilot.org/dev for details
8
9
This program is free software: you can redistribute it and/or modify
10
it under the terms of the GNU General Public License as published by
11
the Free Software Foundation, either version 3 of the License, or
12
(at your option) any later version.
13
14
This program is distributed in the hope that it will be useful,
15
but WITHOUT ANY WARRANTY; without even the implied warranty of
16
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
17
GNU General Public License for more details.
18
19
You should have received a copy of the GNU General Public License
20
along with this program. If not, see <http://www.gnu.org/licenses/>.
21
*/
22
23
#include "Plane.h"
24
25
#define FORCE_VERSION_H_INCLUDE
26
#include "version.h"
27
#undef FORCE_VERSION_H_INCLUDE
28
29
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
30
31
#define SCHED_TASK(func, rate_hz, max_time_micros, priority) SCHED_TASK_CLASS(Plane, &plane, func, rate_hz, max_time_micros, priority)
32
#define FAST_TASK(func) FAST_TASK_CLASS(Plane, &plane, func)
33
34
35
/*
36
scheduler table - all regular tasks should be listed here.
37
38
All entries in this table must be ordered by priority.
39
40
This table is interleaved with the table present in each of the
41
vehicles to determine the order in which tasks are run. Convenience
42
methods SCHED_TASK and SCHED_TASK_CLASS are provided to build
43
entries in this structure:
44
45
SCHED_TASK arguments:
46
- name of static function to call
47
- rate (in Hertz) at which the function should be called
48
- expected time (in MicroSeconds) that the function should take to run
49
- priority (0 through 255, lower number meaning higher priority)
50
51
SCHED_TASK_CLASS arguments:
52
- class name of method to be called
53
- instance on which to call the method
54
- method to call on that instance
55
- rate (in Hertz) at which the method should be called
56
- expected time (in MicroSeconds) that the method should take to run
57
- priority (0 through 255, lower number meaning higher priority)
58
59
FAST_TASK entries are run on every loop even if that means the loop
60
overruns its allotted time
61
*/
62
const AP_Scheduler::Task Plane::scheduler_tasks[] = {
63
// Units: Hz us
64
FAST_TASK(ahrs_update),
65
FAST_TASK(update_control_mode),
66
FAST_TASK(stabilize),
67
FAST_TASK(set_servos),
68
SCHED_TASK(read_radio, 50, 100, 6),
69
SCHED_TASK(check_short_rc_failsafe, 50, 100, 9),
70
SCHED_TASK(update_speed_height, 50, 200, 12),
71
SCHED_TASK(update_throttle_hover, 100, 90, 24),
72
SCHED_TASK_CLASS(RC_Channels, (RC_Channels*)&plane.g2.rc_channels, read_mode_switch, 7, 100, 27),
73
SCHED_TASK(update_GPS_50Hz, 50, 300, 30),
74
SCHED_TASK(update_GPS_10Hz, 10, 400, 33),
75
SCHED_TASK(navigate, 10, 150, 36),
76
SCHED_TASK(update_compass, 10, 200, 39),
77
SCHED_TASK(calc_airspeed_errors, 10, 100, 42),
78
SCHED_TASK(update_alt, 10, 200, 45),
79
SCHED_TASK(adjust_altitude_target, 10, 200, 48),
80
#if AP_ADVANCEDFAILSAFE_ENABLED
81
SCHED_TASK(afs_fs_check, 10, 100, 51),
82
#endif
83
SCHED_TASK(ekf_check, 10, 75, 54),
84
SCHED_TASK_CLASS(GCS, (GCS*)&plane._gcs, update_receive, 300, 500, 57),
85
SCHED_TASK_CLASS(GCS, (GCS*)&plane._gcs, update_send, 300, 750, 60),
86
#if AP_SERVORELAYEVENTS_ENABLED
87
SCHED_TASK_CLASS(AP_ServoRelayEvents, &plane.ServoRelayEvents, update_events, 50, 150, 63),
88
#endif
89
SCHED_TASK_CLASS(AP_BattMonitor, &plane.battery, read, 10, 300, 66),
90
#if AP_RANGEFINDER_ENABLED
91
SCHED_TASK(read_rangefinder, 50, 100, 78),
92
#endif
93
#if AP_ICENGINE_ENABLED
94
SCHED_TASK_CLASS(AP_ICEngine, &plane.g2.ice_control, update, 10, 100, 81),
95
#endif
96
#if AP_OPTICALFLOW_ENABLED
97
SCHED_TASK_CLASS(AP_OpticalFlow, &plane.optflow, update, 50, 50, 87),
98
#endif
99
SCHED_TASK(one_second_loop, 1, 400, 90),
100
SCHED_TASK(three_hz_loop, 3, 75, 93),
101
SCHED_TASK(check_long_failsafe, 3, 400, 96),
102
#if AP_AIRSPEED_AUTOCAL_ENABLE
103
SCHED_TASK(airspeed_ratio_update, 1, 100, 102),
104
#endif // AP_AIRSPEED_AUTOCAL_ENABLE
105
#if HAL_MOUNT_ENABLED
106
SCHED_TASK_CLASS(AP_Mount, &plane.camera_mount, update, 50, 100, 105),
107
#endif // HAL_MOUNT_ENABLED
108
#if AP_CAMERA_ENABLED
109
SCHED_TASK_CLASS(AP_Camera, &plane.camera, update, 50, 100, 108),
110
#endif // CAMERA == ENABLED
111
#if HAL_LOGGING_ENABLED
112
SCHED_TASK_CLASS(AP_Scheduler, &plane.scheduler, update_logging, 0.2, 100, 111),
113
#endif
114
#if HAL_LOGGING_ENABLED
115
SCHED_TASK(Log_Write_FullRate, 400, 300, 117),
116
SCHED_TASK(update_logging10, 10, 300, 120),
117
SCHED_TASK(update_logging25, 25, 300, 123),
118
#endif
119
#if HAL_SOARING_ENABLED
120
SCHED_TASK(update_soaring, 50, 400, 126),
121
#endif
122
SCHED_TASK(parachute_check, 10, 200, 129),
123
#if AP_TERRAIN_AVAILABLE
124
SCHED_TASK_CLASS(AP_Terrain, &plane.terrain, update, 10, 200, 132),
125
#endif // AP_TERRAIN_AVAILABLE
126
SCHED_TASK(update_is_flying_5Hz, 5, 100, 135),
127
#if HAL_LOGGING_ENABLED
128
SCHED_TASK_CLASS(AP_Logger, &plane.logger, periodic_tasks, 50, 400, 138),
129
#endif
130
SCHED_TASK_CLASS(AP_InertialSensor, &plane.ins, periodic, 50, 50, 141),
131
#if HAL_ADSB_ENABLED || AP_ADSB_AVOIDANCE_ENABLED
132
SCHED_TASK(avoidance_adsb_update, 10, 100, 144),
133
#endif // HAL_ADSB_ENABLED || AP_ADSB_AVOIDANCE_ENABLED
134
SCHED_TASK_CLASS(RC_Channels, (RC_Channels*)&plane.g2.rc_channels, read_aux_all, 10, 200, 147),
135
#if HAL_BUTTON_ENABLED
136
SCHED_TASK_CLASS(AP_Button, &plane.button, update, 5, 100, 150),
137
#endif
138
#if AP_LANDINGGEAR_ENABLED
139
SCHED_TASK(landing_gear_update, 5, 50, 159),
140
#endif
141
#if AC_PRECLAND_ENABLED
142
SCHED_TASK(precland_update, 400, 50, 160),
143
#endif
144
#if AP_QUICKTUNE_ENABLED
145
SCHED_TASK(update_quicktune, 40, 100, 163),
146
#endif
147
};
148
149
void Plane::get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
150
uint8_t &task_count,
151
uint32_t &log_bit)
152
{
153
tasks = &scheduler_tasks[0];
154
task_count = ARRAY_SIZE(scheduler_tasks);
155
log_bit = MASK_LOG_PM;
156
}
157
158
#if HAL_QUADPLANE_ENABLED
159
constexpr int8_t Plane::_failsafe_priorities[7];
160
#else
161
constexpr int8_t Plane::_failsafe_priorities[6];
162
#endif
163
164
// update AHRS system
165
void Plane::ahrs_update()
166
{
167
arming.update_soft_armed();
168
169
ahrs.update();
170
171
#if HAL_LOGGING_ENABLED
172
if (should_log(MASK_LOG_IMU)) {
173
AP::ins().Write_IMU();
174
}
175
#endif
176
177
// calculate a scaled roll limit based on current pitch
178
roll_limit_cd = aparm.roll_limit*100;
179
pitch_limit_min = aparm.pitch_limit_min;
180
181
bool rotate_limits = true;
182
#if HAL_QUADPLANE_ENABLED
183
if (quadplane.tailsitter.active()) {
184
rotate_limits = false;
185
}
186
#endif
187
if (rotate_limits) {
188
roll_limit_cd *= ahrs.cos_pitch();
189
pitch_limit_min *= fabsf(ahrs.cos_roll());
190
}
191
192
// updated the summed gyro used for ground steering and
193
// auto-takeoff. Dot product of DCM.c with gyro vector gives earth
194
// frame yaw rate
195
steer_state.locked_course_err += ahrs.get_yaw_rate_earth() * G_Dt;
196
steer_state.locked_course_err = wrap_PI(steer_state.locked_course_err);
197
198
#if HAL_QUADPLANE_ENABLED
199
// check if we have had a yaw reset from the EKF
200
quadplane.check_yaw_reset();
201
202
// update inertial_nav for quadplane
203
quadplane.inertial_nav.update();
204
if (quadplane.available()) {
205
quadplane.pos_control->update_estimates();
206
}
207
#endif
208
#if AP_SCRIPTING_ENABLED && AP_FOLLOW_ENABLED
209
g2.follow.update_estimates();
210
#endif
211
212
#if HAL_LOGGING_ENABLED
213
if (should_log(MASK_LOG_VIDEO_STABILISATION)) {
214
ahrs.write_video_stabilisation();
215
}
216
#endif
217
}
218
219
/*
220
update 50Hz speed/height controller
221
*/
222
void Plane::update_speed_height(void)
223
{
224
bool should_run_tecs = control_mode->does_auto_throttle();
225
#if HAL_QUADPLANE_ENABLED
226
if (quadplane.should_disable_TECS()) {
227
should_run_tecs = false;
228
}
229
#endif
230
231
if (auto_state.idle_mode) {
232
should_run_tecs = false;
233
}
234
235
#if AP_PLANE_GLIDER_PULLUP_ENABLED
236
if (mode_auto.in_pullup()) {
237
should_run_tecs = false;
238
}
239
#endif
240
241
if (should_run_tecs) {
242
// Call TECS 50Hz update. Note that we call this regardless of
243
// throttle suppressed, as this needs to be running for
244
// takeoff detection
245
TECS_controller.update_50hz();
246
}
247
248
#if HAL_QUADPLANE_ENABLED
249
if (quadplane.in_vtol_mode() ||
250
quadplane.in_assisted_flight()) {
251
quadplane.update_throttle_mix();
252
}
253
#endif
254
}
255
256
257
/*
258
read and update compass
259
*/
260
void Plane::update_compass(void)
261
{
262
compass.read();
263
}
264
265
#if HAL_LOGGING_ENABLED
266
/*
267
do 10Hz logging
268
*/
269
void Plane::update_logging10(void)
270
{
271
bool log_faster = (should_log(MASK_LOG_ATTITUDE_FULLRATE) || should_log(MASK_LOG_ATTITUDE_FAST));
272
if (should_log(MASK_LOG_ATTITUDE_MED) && !log_faster) {
273
Log_Write_Attitude();
274
ahrs.Write_AOA_SSA();
275
} else if (log_faster) {
276
ahrs.Write_AOA_SSA();
277
}
278
#if HAL_MOUNT_ENABLED
279
if (should_log(MASK_LOG_CAMERA)) {
280
camera_mount.write_log();
281
}
282
#endif
283
}
284
285
/*
286
do 25Hz logging
287
*/
288
void Plane::update_logging25(void)
289
{
290
// MASK_LOG_ATTITUDE_FULLRATE logs at 400Hz, MASK_LOG_ATTITUDE_FAST at 25Hz, MASK_LOG_ATTIUDE_MED logs at 10Hz
291
// highest rate selected wins
292
bool log_faster = should_log(MASK_LOG_ATTITUDE_FULLRATE);
293
if (should_log(MASK_LOG_ATTITUDE_FAST) && !log_faster) {
294
Log_Write_Attitude();
295
}
296
297
if (should_log(MASK_LOG_CTUN)) {
298
Log_Write_Control_Tuning();
299
#if AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED
300
if (!should_log(MASK_LOG_NOTCH_FULLRATE)) {
301
AP::ins().write_notch_log_messages();
302
}
303
#endif
304
#if HAL_GYROFFT_ENABLED
305
gyro_fft.write_log_messages();
306
#endif
307
}
308
309
if (should_log(MASK_LOG_NTUN)) {
310
Log_Write_Nav_Tuning();
311
Log_Write_Guided();
312
}
313
314
if (should_log(MASK_LOG_RC))
315
Log_Write_RC();
316
317
if (should_log(MASK_LOG_IMU))
318
AP::ins().Write_Vibration();
319
320
#if AP_PLANE_BLACKBOX_LOGGING
321
Log_Write_Blackbox();
322
#endif
323
}
324
#endif // HAL_LOGGING_ENABLED
325
326
/*
327
check for AFS failsafe check
328
*/
329
#if AP_ADVANCEDFAILSAFE_ENABLED
330
void Plane::afs_fs_check(void)
331
{
332
afs.check(failsafe.AFS_last_valid_rc_ms);
333
}
334
#endif
335
336
#if HAL_WITH_IO_MCU
337
#include <AP_IOMCU/AP_IOMCU.h>
338
extern AP_IOMCU iomcu;
339
#endif
340
341
void Plane::one_second_loop()
342
{
343
// make it possible to change control channel ordering at runtime
344
set_control_channels();
345
346
#if HAL_WITH_IO_MCU
347
iomcu.setup_mixing(g.override_channel.get(), g.mixing_gain, g2.manual_rc_mask);
348
#endif
349
350
#if HAL_ADSB_ENABLED
351
adsb.set_stall_speed_cm(aparm.airspeed_min * 100); // convert m/s to cm/s
352
adsb.set_max_speed(aparm.airspeed_max);
353
#endif
354
355
if (flight_option_enabled(FlightOptions::ENABLE_DEFAULT_AIRSPEED)) {
356
// use average of min and max airspeed as default airspeed fusion with high variance
357
ahrs.writeDefaultAirSpeed((float)((aparm.airspeed_min + aparm.airspeed_max)/2),
358
(float)((aparm.airspeed_max - aparm.airspeed_min)/2));
359
}
360
361
AP::srv().enable_aux_servos();
362
363
// update notify flags
364
AP_Notify::flags.pre_arm_check = arming.pre_arm_checks(false);
365
AP_Notify::flags.pre_arm_gps_check = true;
366
AP_Notify::flags.armed = arming.is_armed() || arming.arming_required() == AP_Arming::Required::NO;
367
368
#if AP_TERRAIN_AVAILABLE && HAL_LOGGING_ENABLED
369
if (should_log(MASK_LOG_GPS)) {
370
terrain.log_terrain_data();
371
}
372
#endif
373
374
// update home position if NOT armed and gps position has
375
// changed. Update every 5s at most
376
if (!arming.is_armed() &&
377
gps.last_message_time_ms() - last_home_update_ms > 5000 &&
378
gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
379
last_home_update_ms = gps.last_message_time_ms();
380
update_home();
381
382
// reset the landing altitude correction
383
landing.alt_offset = 0;
384
}
385
386
const float loop_rate = AP::scheduler().get_filtered_loop_rate_hz();
387
#if HAL_QUADPLANE_ENABLED
388
if (quadplane.available()) {
389
quadplane.attitude_control->set_notch_sample_rate(loop_rate);
390
}
391
#endif
392
rollController.set_notch_sample_rate(loop_rate);
393
pitchController.set_notch_sample_rate(loop_rate);
394
yawController.set_notch_sample_rate(loop_rate);
395
}
396
397
void Plane::three_hz_loop()
398
{
399
#if AP_FENCE_ENABLED
400
fence_check();
401
#endif
402
}
403
404
#if AP_AIRSPEED_AUTOCAL_ENABLE
405
/*
406
once a second update the airspeed calibration ratio
407
*/
408
void Plane::airspeed_ratio_update(void)
409
{
410
if (!hal.util->get_soft_armed() ||
411
!ahrs.get_fly_forward() ||
412
!is_flying() ||
413
!airspeed.enabled() ||
414
gps.status() < AP_GPS::GPS_OK_FIX_3D ||
415
gps.ground_speed() < 4) {
416
// don't calibrate when not moving
417
return;
418
}
419
if (airspeed.get_airspeed() < aparm.airspeed_min &&
420
gps.ground_speed() < (uint32_t)aparm.airspeed_min) {
421
// don't calibrate when flying below the minimum airspeed. We
422
// check both airspeed and ground speed to catch cases where
423
// the airspeed ratio is way too low, which could lead to it
424
// never coming up again
425
return;
426
}
427
if (labs(ahrs.roll_sensor) > roll_limit_cd ||
428
ahrs.get_pitch_deg() > aparm.pitch_limit_max ||
429
ahrs.get_pitch_deg() < pitch_limit_min) {
430
// don't calibrate when going beyond normal flight envelope
431
return;
432
}
433
const Vector3f &vg = gps.velocity();
434
airspeed.update_calibration(vg, aparm.airspeed_max);
435
}
436
#endif // AP_AIRSPEED_AUTOCAL_ENABLE
437
438
/*
439
read the GPS and update position
440
*/
441
void Plane::update_GPS_50Hz(void)
442
{
443
gps.update();
444
445
update_current_loc();
446
}
447
448
/*
449
read update GPS position - 10Hz update
450
*/
451
void Plane::update_GPS_10Hz(void)
452
{
453
static uint32_t last_gps_msg_ms;
454
if (gps.last_message_time_ms() != last_gps_msg_ms && gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
455
last_gps_msg_ms = gps.last_message_time_ms();
456
457
if (ground_start_count > 1) {
458
ground_start_count--;
459
} else if (ground_start_count == 1) {
460
// We countdown N number of good GPS fixes
461
// so that the altitude is more accurate
462
// -------------------------------------
463
if (current_loc.lat == 0 && current_loc.lng == 0) {
464
ground_start_count = 5;
465
466
} else if (!hal.util->was_watchdog_reset()) {
467
if (!set_home_persistently(gps.location())) {
468
// silently ignore failure...
469
}
470
471
next_WP_loc = prev_WP_loc = home;
472
473
ground_start_count = 0;
474
}
475
}
476
477
// update wind estimate
478
ahrs.estimate_wind();
479
} else if (gps.status() < AP_GPS::GPS_OK_FIX_3D && ground_start_count != 0) {
480
// lost 3D fix, start again
481
ground_start_count = 5;
482
}
483
484
calc_gndspeed_undershoot();
485
}
486
487
/*
488
main control mode dependent update code
489
*/
490
void Plane::update_control_mode(void)
491
{
492
if ((control_mode != &mode_auto) && (control_mode != &mode_takeoff)) {
493
// hold_course is only used in takeoff and landing
494
steer_state.hold_course_cd = -1;
495
}
496
// refresh the throttle limits, to avoid using stale values
497
// they will be updated once takeoff_calc_throttle is called
498
takeoff_state.throttle_lim_max = 100.0f;
499
takeoff_state.throttle_lim_min = -100.0f;
500
501
update_fly_forward();
502
503
control_mode->update();
504
505
#if MODE_AUTOLAND_ENABLED
506
mode_autoland.check_takeoff_direction();
507
#endif
508
}
509
510
511
void Plane::update_fly_forward(void)
512
{
513
// ensure we are fly-forward when we are flying as a pure fixed
514
// wing aircraft. This helps the EKF produce better state
515
// estimates as it can make stronger assumptions
516
#if HAL_QUADPLANE_ENABLED
517
if (quadplane.available()) {
518
if (quadplane.tailsitter.is_in_fw_flight()) {
519
ahrs.set_fly_forward(true);
520
return;
521
}
522
523
if (quadplane.in_vtol_mode()) {
524
ahrs.set_fly_forward(false);
525
return;
526
}
527
528
if (quadplane.in_assisted_flight()) {
529
ahrs.set_fly_forward(false);
530
return;
531
}
532
}
533
#endif
534
535
if (auto_state.idle_mode) {
536
// don't fuse airspeed when in balloon lift
537
ahrs.set_fly_forward(false);
538
return;
539
}
540
541
if (flight_stage == AP_FixedWing::FlightStage::LAND) {
542
ahrs.set_fly_forward(landing.is_flying_forward());
543
return;
544
}
545
546
ahrs.set_fly_forward(true);
547
}
548
549
/*
550
set the flight stage
551
*/
552
void Plane::set_flight_stage(AP_FixedWing::FlightStage fs)
553
{
554
if (fs == flight_stage) {
555
return;
556
}
557
558
const bool is_landing = (fs == AP_FixedWing::FlightStage::LAND);
559
560
landing.handle_flight_stage_change(is_landing);
561
562
#if AP_LANDINGGEAR_ENABLED
563
if (is_landing) {
564
plane.g2.landing_gear.deploy_for_landing();
565
}
566
567
const bool is_takeoff_complete = (flight_stage == AP_FixedWing::FlightStage::TAKEOFF &&
568
fs == AP_FixedWing::FlightStage::NORMAL);
569
if (is_takeoff_complete &&
570
arming.is_armed_and_safety_off() &&
571
is_flying()) {
572
g2.landing_gear.retract_after_takeoff();
573
}
574
#endif
575
576
if (fs == AP_FixedWing::FlightStage::ABORT_LANDING) {
577
gcs().send_text(MAV_SEVERITY_NOTICE, "Landing aborted, climbing to %dm",
578
int(auto_state.takeoff_altitude_rel_cm/100));
579
}
580
581
flight_stage = fs;
582
#if HAL_LOGGING_ENABLED
583
Log_Write_Status();
584
#endif
585
}
586
587
void Plane::update_alt()
588
{
589
barometer.update();
590
591
// calculate the sink rate.
592
float sink_rate;
593
Vector3f vel;
594
if (ahrs.get_velocity_NED(vel)) {
595
sink_rate = vel.z;
596
} else if (gps.status() >= AP_GPS::GPS_OK_FIX_3D && gps.have_vertical_velocity()) {
597
sink_rate = gps.velocity().z;
598
} else {
599
sink_rate = -barometer.get_climb_rate();
600
}
601
602
// low pass the sink rate to take some of the noise out
603
auto_state.sink_rate = 0.8f * auto_state.sink_rate + 0.2f*sink_rate;
604
#if HAL_PARACHUTE_ENABLED
605
parachute.set_sink_rate(auto_state.sink_rate);
606
#endif
607
608
update_flight_stage();
609
610
#if AP_SCRIPTING_ENABLED
611
if (nav_scripting_active()) {
612
// don't call TECS while we are in a trick
613
return;
614
}
615
#endif
616
617
bool should_run_tecs = control_mode->does_auto_throttle();
618
#if HAL_QUADPLANE_ENABLED
619
if (quadplane.should_disable_TECS()) {
620
should_run_tecs = false;
621
}
622
#endif
623
624
if (auto_state.idle_mode) {
625
should_run_tecs = false;
626
}
627
628
#if AP_PLANE_GLIDER_PULLUP_ENABLED
629
if (mode_auto.in_pullup()) {
630
should_run_tecs = false;
631
}
632
#endif
633
634
if (should_run_tecs && !throttle_suppressed) {
635
636
float distance_beyond_land_wp = 0;
637
if (flight_stage == AP_FixedWing::FlightStage::LAND &&
638
current_loc.past_interval_finish_line(prev_WP_loc, next_WP_loc)) {
639
distance_beyond_land_wp = current_loc.get_distance(next_WP_loc);
640
}
641
642
tecs_target_alt_cm = relative_target_altitude_cm();
643
644
if (control_mode == &mode_rtl && !rtl.done_climb && (g2.rtl_climb_min > 0 || (plane.flight_option_enabled(FlightOptions::CLIMB_BEFORE_TURN)))) {
645
// ensure we do the initial climb in RTL. We add an extra
646
// 10m in the demanded height to push TECS to climb
647
// quickly
648
tecs_target_alt_cm = MAX(tecs_target_alt_cm, prev_WP_loc.alt - home.alt) + (g2.rtl_climb_min+10)*100;
649
}
650
651
TECS_controller.update_pitch_throttle(tecs_target_alt_cm,
652
target_airspeed_cm,
653
flight_stage,
654
distance_beyond_land_wp,
655
get_takeoff_pitch_min_cd(),
656
throttle_nudge,
657
tecs_hgt_afe(),
658
aerodynamic_load_factor,
659
g.pitch_trim.get());
660
}
661
}
662
663
/*
664
recalculate the flight_stage
665
*/
666
void Plane::update_flight_stage(void)
667
{
668
// Update the speed & height controller states
669
if (control_mode->does_auto_throttle() && !throttle_suppressed) {
670
if (control_mode == &mode_auto) {
671
#if HAL_QUADPLANE_ENABLED
672
if (quadplane.in_vtol_auto()) {
673
set_flight_stage(AP_FixedWing::FlightStage::VTOL);
674
return;
675
}
676
#endif
677
if (auto_state.takeoff_complete == false) {
678
set_flight_stage(AP_FixedWing::FlightStage::TAKEOFF);
679
return;
680
} else if (mission.get_current_nav_cmd().id == MAV_CMD_NAV_LAND) {
681
if (landing.is_commanded_go_around() || flight_stage == AP_FixedWing::FlightStage::ABORT_LANDING) {
682
// abort mode is sticky, it must complete while executing NAV_LAND
683
set_flight_stage(AP_FixedWing::FlightStage::ABORT_LANDING);
684
} else if (landing.get_abort_throttle_enable() && get_throttle_input() >= 90 &&
685
landing.request_go_around()) {
686
gcs().send_text(MAV_SEVERITY_INFO,"Landing aborted via throttle");
687
set_flight_stage(AP_FixedWing::FlightStage::ABORT_LANDING);
688
} else {
689
set_flight_stage(AP_FixedWing::FlightStage::LAND);
690
}
691
return;
692
}
693
#if HAL_QUADPLANE_ENABLED
694
if (quadplane.in_assisted_flight()) {
695
set_flight_stage(AP_FixedWing::FlightStage::VTOL);
696
return;
697
}
698
#endif
699
set_flight_stage(AP_FixedWing::FlightStage::NORMAL);
700
} else if ((control_mode != &mode_takeoff)
701
#if MODE_AUTOLAND_ENABLED
702
&& (control_mode != &mode_autoland)
703
#endif
704
) {
705
// If not in AUTO then assume normal operation for normal TECS operation.
706
// This prevents TECS from being stuck in the wrong stage if you switch from
707
// AUTO to, say, FBWB during a landing, an aborted landing or takeoff.
708
set_flight_stage(AP_FixedWing::FlightStage::NORMAL);
709
}
710
return;
711
}
712
#if HAL_QUADPLANE_ENABLED
713
if (quadplane.in_vtol_mode() ||
714
quadplane.in_assisted_flight()) {
715
set_flight_stage(AP_FixedWing::FlightStage::VTOL);
716
return;
717
}
718
#endif
719
set_flight_stage(AP_FixedWing::FlightStage::NORMAL);
720
}
721
722
723
724
725
/*
726
If land_DisarmDelay is enabled (non-zero), check for a landing then auto-disarm after time expires
727
728
only called from AP_Landing, when the landing library is ready to disarm
729
*/
730
void Plane::disarm_if_autoland_complete()
731
{
732
if (landing.get_disarm_delay() > 0 &&
733
!is_flying() &&
734
arming.arming_required() != AP_Arming::Required::NO &&
735
arming.is_armed()) {
736
/* we have auto disarm enabled. See if enough time has passed */
737
if (millis() - auto_state.last_flying_ms >= landing.get_disarm_delay()*1000UL) {
738
if (arming.disarm(AP_Arming::Method::AUTOLANDED)) {
739
gcs().send_text(MAV_SEVERITY_INFO,"Auto disarmed");
740
}
741
}
742
}
743
}
744
745
bool Plane::trigger_land_abort(const float climb_to_alt_m)
746
{
747
if (plane.control_mode != &plane.mode_auto) {
748
return false;
749
}
750
#if HAL_QUADPLANE_ENABLED
751
if (plane.quadplane.in_vtol_auto()) {
752
return quadplane.abort_landing();
753
}
754
#endif
755
756
uint16_t mission_id = plane.mission.get_current_nav_cmd().id;
757
bool is_in_landing = (plane.flight_stage == AP_FixedWing::FlightStage::LAND) ||
758
plane.is_land_command(mission_id);
759
if (is_in_landing) {
760
// fly a user planned abort pattern if available
761
if (plane.have_position && plane.mission.jump_to_abort_landing_sequence(plane.current_loc)) {
762
return true;
763
}
764
765
// only fly a fixed wing abort if we aren't doing quadplane stuff, or potentially
766
// shooting a quadplane approach
767
#if HAL_QUADPLANE_ENABLED
768
const bool attempt_go_around =
769
(!plane.quadplane.available()) ||
770
((!plane.quadplane.in_vtol_auto()) &&
771
(!plane.quadplane.landing_with_fixed_wing_spiral_approach()));
772
#else
773
const bool attempt_go_around = true;
774
#endif
775
if (attempt_go_around) {
776
// Initiate an aborted landing. This will trigger a pitch-up and
777
// climb-out to a safe altitude holding heading then one of the
778
// following actions will occur, check for in this order:
779
// - If MAV_CMD_CONTINUE_AND_CHANGE_ALT is next command in mission,
780
// increment mission index to execute it
781
// - else if DO_LAND_START is available, jump to it
782
// - else decrement the mission index to repeat the landing approach
783
784
if (!is_zero(climb_to_alt_m)) {
785
plane.auto_state.takeoff_altitude_rel_cm = climb_to_alt_m * 100;
786
}
787
if (plane.landing.request_go_around()) {
788
plane.auto_state.next_wp_crosstrack = false;
789
return true;
790
}
791
}
792
}
793
return false;
794
}
795
796
797
/*
798
the height above field elevation that we pass to TECS
799
*/
800
float Plane::tecs_hgt_afe(void)
801
{
802
/*
803
pass the height above field elevation as the height above
804
the ground when in landing, which means that TECS gets the
805
rangefinder information and thus can know when the flare is
806
coming.
807
*/
808
float hgt_afe;
809
810
if (flight_stage == AP_FixedWing::FlightStage::LAND) {
811
812
#if AP_MAVLINK_MAV_CMD_SET_HAGL_ENABLED
813
// if external HAGL is active use that
814
if (get_external_HAGL(hgt_afe)) {
815
return hgt_afe;
816
}
817
#endif
818
819
hgt_afe = height_above_target();
820
#if AP_RANGEFINDER_ENABLED
821
hgt_afe -= rangefinder_correction();
822
#endif
823
} else {
824
// when in normal flight we pass the hgt_afe as relative
825
// altitude to home
826
hgt_afe = relative_altitude;
827
}
828
return hgt_afe;
829
}
830
831
// vehicle specific waypoint info helpers
832
bool Plane::get_wp_distance_m(float &distance) const
833
{
834
// see GCS_MAVLINK_Plane::send_nav_controller_output()
835
if (control_mode == &mode_manual) {
836
return false;
837
}
838
#if HAL_QUADPLANE_ENABLED
839
if (quadplane.in_vtol_mode()) {
840
distance = quadplane.using_wp_nav() ? quadplane.wp_nav->get_wp_distance_to_destination_m() : 0;
841
return true;
842
}
843
#endif
844
distance = auto_state.wp_distance;
845
return true;
846
}
847
848
bool Plane::get_wp_bearing_deg(float &bearing) const
849
{
850
// see GCS_MAVLINK_Plane::send_nav_controller_output()
851
if (control_mode == &mode_manual) {
852
return false;
853
}
854
#if HAL_QUADPLANE_ENABLED
855
if (quadplane.in_vtol_mode()) {
856
bearing = quadplane.using_wp_nav() ? quadplane.wp_nav->get_wp_bearing_to_destination_cd() : 0;
857
return true;
858
}
859
#endif
860
bearing = nav_controller->target_bearing_cd() * 0.01;
861
return true;
862
}
863
864
bool Plane::get_wp_crosstrack_error_m(float &xtrack_error) const
865
{
866
// see GCS_MAVLINK_Plane::send_nav_controller_output()
867
if (control_mode == &mode_manual) {
868
return false;
869
}
870
#if HAL_QUADPLANE_ENABLED
871
if (quadplane.in_vtol_mode()) {
872
xtrack_error = quadplane.using_wp_nav() ? quadplane.wp_nav->crosstrack_error_m() : 0;
873
return true;
874
}
875
#endif
876
xtrack_error = nav_controller->crosstrack_error();
877
return true;
878
}
879
880
#if AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED
881
// set target location (for use by external control and scripting)
882
bool Plane::set_target_location(const Location &target_loc)
883
{
884
Location loc{target_loc};
885
fix_terrain_WP(loc, __LINE__);
886
887
if (plane.control_mode != &plane.mode_guided) {
888
// only accept position updates when in GUIDED mode
889
return false;
890
}
891
// add home alt if needed
892
if (!loc.terrain_alt) {
893
loc.change_alt_frame(Location::AltFrame::ABSOLUTE);
894
}
895
plane.set_guided_WP(loc);
896
return true;
897
}
898
#endif //AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED
899
900
#if AP_SCRIPTING_ENABLED
901
// get target location (for use by scripting)
902
bool Plane::get_target_location(Location& target_loc)
903
{
904
switch (control_mode->mode_number()) {
905
case Mode::Number::RTL:
906
case Mode::Number::AVOID_ADSB:
907
case Mode::Number::GUIDED:
908
case Mode::Number::AUTO:
909
case Mode::Number::LOITER:
910
case Mode::Number::TAKEOFF:
911
#if HAL_QUADPLANE_ENABLED
912
case Mode::Number::QLOITER:
913
case Mode::Number::QLAND:
914
case Mode::Number::QRTL:
915
#endif
916
target_loc = next_WP_loc;
917
return true;
918
break;
919
default:
920
break;
921
}
922
return false;
923
}
924
925
/*
926
update_target_location() works in all auto navigation modes
927
*/
928
bool Plane::update_target_location(const Location &old_loc, const Location &new_loc)
929
{
930
/*
931
by checking the caller has provided the correct old target
932
location we prevent a race condition where the user changes mode
933
or commands a different target in the controlling lua script
934
*/
935
if (!old_loc.same_loc_as(next_WP_loc) ||
936
old_loc.get_alt_frame() != new_loc.get_alt_frame()) {
937
return false;
938
}
939
next_WP_loc = new_loc;
940
941
fix_terrain_WP(next_WP_loc, __LINE__);
942
943
#if HAL_QUADPLANE_ENABLED
944
if (control_mode == &mode_qland || control_mode == &mode_qloiter) {
945
mode_qloiter.last_target_loc_set_ms = AP_HAL::millis();
946
}
947
#endif
948
949
return true;
950
}
951
952
// allow for velocity matching in VTOL
953
bool Plane::set_velocity_match(const Vector2f &velocity)
954
{
955
#if HAL_QUADPLANE_ENABLED
956
if (quadplane.in_vtol_mode() || quadplane.in_vtol_land_sequence()) {
957
quadplane.poscontrol.velocity_match_ms = velocity;
958
quadplane.poscontrol.last_velocity_match_ms = AP_HAL::millis();
959
return true;
960
}
961
#endif
962
return false;
963
}
964
965
// allow for override of land descent rate
966
bool Plane::set_land_descent_rate(float descent_rate)
967
{
968
#if HAL_QUADPLANE_ENABLED
969
if (quadplane.in_vtol_land_descent() ||
970
control_mode == &mode_qland) {
971
quadplane.poscontrol.override_descent_rate_ms = descent_rate;
972
quadplane.poscontrol.last_override_descent_ms = AP_HAL::millis();
973
return true;
974
}
975
#endif
976
return false;
977
}
978
979
// Allow for scripting to have control over the crosstracking when exiting and resuming missions or guided flight
980
// It's up to the Lua script to ensure the provided location makes sense
981
bool Plane::set_crosstrack_start(const Location &new_start_location)
982
{
983
prev_WP_loc = new_start_location;
984
auto_state.crosstrack = true;
985
return true;
986
}
987
988
#endif // AP_SCRIPTING_ENABLED
989
990
// returns true if vehicle is landing.
991
bool Plane::is_landing() const
992
{
993
#if HAL_QUADPLANE_ENABLED
994
if (plane.quadplane.in_vtol_land_descent()) {
995
return true;
996
}
997
#endif
998
return control_mode->is_landing();
999
}
1000
1001
// returns true if vehicle is taking off.
1002
bool Plane::is_taking_off() const
1003
{
1004
#if HAL_QUADPLANE_ENABLED
1005
if (plane.quadplane.in_vtol_takeoff()) {
1006
return true;
1007
}
1008
#endif
1009
return control_mode->is_taking_off();
1010
}
1011
1012
#if HAL_QUADPLANE_ENABLED
1013
bool Plane::start_takeoff(const float alt_m) {
1014
return plane.quadplane.available() && quadplane.do_user_takeoff(alt_m);
1015
}
1016
#endif
1017
1018
// correct AHRS pitch for PTCH_TRIM_DEG in non-VTOL modes, and return VTOL view in VTOL
1019
void Plane::get_osd_roll_pitch_rad(float &roll, float &pitch) const
1020
{
1021
#if HAL_QUADPLANE_ENABLED
1022
if (quadplane.show_vtol_view()) {
1023
pitch = quadplane.ahrs_view->pitch;
1024
roll = quadplane.ahrs_view->roll;
1025
return;
1026
}
1027
#endif
1028
pitch = ahrs.get_pitch_rad();
1029
roll = ahrs.get_roll_rad();
1030
if (!(flight_option_enabled(FlightOptions::OSD_REMOVE_TRIM_PITCH))) { // correct for PTCH_TRIM_DEG
1031
pitch -= g.pitch_trim * DEG_TO_RAD;
1032
}
1033
}
1034
1035
/*
1036
update current_loc Location
1037
*/
1038
void Plane::update_current_loc(void)
1039
{
1040
have_position = plane.ahrs.get_location(plane.current_loc);
1041
1042
// re-calculate relative altitude
1043
ahrs.get_relative_position_D_home(plane.relative_altitude);
1044
relative_altitude *= -1.0f;
1045
}
1046
1047
// check if FLIGHT_OPTION is enabled
1048
bool Plane::flight_option_enabled(FlightOptions flight_option) const
1049
{
1050
return g2.flight_options & flight_option;
1051
}
1052
1053
#if AC_PRECLAND_ENABLED
1054
void Plane::precland_update(void)
1055
{
1056
// alt will be unused if we pass false through as the second parameter:
1057
#if AP_RANGEFINDER_ENABLED
1058
return g2.precland.update(rangefinder_state.height_estimate*100, rangefinder_state.in_range);
1059
#else
1060
return g2.precland.update(0, false);
1061
#endif
1062
}
1063
#endif
1064
1065
#if AP_QUICKTUNE_ENABLED
1066
/*
1067
update AP_Quicktune object. We pass the supports_quicktune() method
1068
in so that quicktune can detect if the user changes to a
1069
non-quicktune capable mode while tuning and the gains can be reverted
1070
*/
1071
void Plane::update_quicktune(void)
1072
{
1073
quicktune.update(control_mode->supports_quicktune());
1074
}
1075
#endif
1076
1077
/*
1078
constructor for main Plane class
1079
*/
1080
Plane::Plane(void)
1081
{
1082
// C++11 doesn't allow in-class initialisation of bitfields
1083
auto_state.takeoff_complete = true;
1084
}
1085
1086
Plane plane;
1087
AP_Vehicle& vehicle = plane;
1088
1089
AP_HAL_MAIN_CALLBACKS(&plane);
1090
1091