CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

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