forked from ArduPilot/ardupilot
-
Notifications
You must be signed in to change notification settings - Fork 26
/
Copy pathmode.h
808 lines (550 loc) · 20.4 KB
/
mode.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
#pragma once
#include <AP_Param/AP_Param.h>
#include <AP_Common/Location.h>
#include <stdint.h>
#include <AP_Soaring/AP_Soaring.h>
#include <AP_ADSB/AP_ADSB.h>
#include <AP_Vehicle/ModeReason.h>
#include "quadplane.h"
#include <AP_AHRS/AP_AHRS.h>
class AC_PosControl;
class AC_AttitudeControl_Multi;
class AC_Loiter;
class Mode
{
public:
/* Do not allow copies */
CLASS_NO_COPY(Mode);
// Auto Pilot modes
// ----------------
enum Number : uint8_t {
MANUAL = 0,
CIRCLE = 1,
STABILIZE = 2,
TRAINING = 3,
ACRO = 4,
FLY_BY_WIRE_A = 5,
FLY_BY_WIRE_B = 6,
CRUISE = 7,
AUTOTUNE = 8,
AUTO = 10,
RTL = 11,
LOITER = 12,
TAKEOFF = 13,
AVOID_ADSB = 14,
GUIDED = 15,
INITIALISING = 16,
#if HAL_QUADPLANE_ENABLED
QSTABILIZE = 17,
QHOVER = 18,
QLOITER = 19,
QLAND = 20,
QRTL = 21,
#if QAUTOTUNE_ENABLED
QAUTOTUNE = 22,
#endif
QACRO = 23,
#endif
THERMAL = 24,
#if HAL_QUADPLANE_ENABLED
LOITER_ALT_QLAND = 25,
#endif
};
// Constructor
Mode();
// enter this mode, always returns true/success
bool enter();
// perform any cleanups required:
void exit();
// run controllers specific to this mode
virtual void run();
// returns a unique number specific to this mode
virtual Number mode_number() const = 0;
// returns full text name
virtual const char *name() const = 0;
// returns a string for this flightmode, exactly 4 bytes
virtual const char *name4() const = 0;
// returns true if the vehicle can be armed in this mode
bool pre_arm_checks(size_t buflen, char *buffer) const;
// Reset rate and steering controllers
void reset_controllers();
//
// methods that sub classes should override to affect movement of the vehicle in this mode
//
// convert user input to targets, implement high level control for this mode
virtual void update() = 0;
// true for all q modes
virtual bool is_vtol_mode() const { return false; }
virtual bool is_vtol_man_throttle() const;
virtual bool is_vtol_man_mode() const { return false; }
// guided or adsb mode
virtual bool is_guided_mode() const { return false; }
// true if mode can have terrain following disabled by switch
virtual bool allows_terrain_disable() const { return false; }
// true if automatic switch to thermal mode is supported.
virtual bool does_automatic_thermal_switch() const {return false; }
// subclasses override this if they require navigation.
virtual void navigate() { return; }
// this allows certain flight modes to mix RC input with throttle
// depending on airspeed_nudge_cm
virtual bool allows_throttle_nudging() const { return false; }
// true if the mode sets the vehicle destination, which controls
// whether control input is ignored with STICK_MIXING=0
virtual bool does_auto_navigation() const { return false; }
// true if the mode sets the vehicle destination, which controls
// whether control input is ignored with STICK_MIXING=0
virtual bool does_auto_throttle() const { return false; }
// true if the mode supports autotuning (via switch for modes other
// that AUTOTUNE itself
virtual bool mode_allows_autotuning() const { return false; }
// method for mode specific target altitude profiles
virtual void update_target_altitude();
// handle a guided target request from GCS
virtual bool handle_guided_request(Location target_loc) { return false; }
// true if is landing
virtual bool is_landing() const { return false; }
// true if is taking
virtual bool is_taking_off() const;
protected:
// subclasses override this to perform checks before entering the mode
virtual bool _enter() { return true; }
// subclasses override this to perform any required cleanup when exiting the mode
virtual void _exit() { return; }
// mode specific pre-arm checks
virtual bool _pre_arm_checks(size_t buflen, char *buffer) const;
#if HAL_QUADPLANE_ENABLED
// References for convenience, used by QModes
AC_PosControl*& pos_control;
AC_AttitudeControl_Multi*& attitude_control;
AC_Loiter*& loiter_nav;
QuadPlane& quadplane;
QuadPlane::PosControlState &poscontrol;
#endif
AP_AHRS& ahrs;
};
class ModeAcro : public Mode
{
friend class ModeQAcro;
public:
Mode::Number mode_number() const override { return Mode::Number::ACRO; }
const char *name() const override { return "ACRO"; }
const char *name4() const override { return "ACRO"; }
// methods that affect movement of the vehicle in this mode
void update() override;
void run() override;
void stabilize();
void stabilize_quaternion();
protected:
// ACRO controller state
struct {
bool locked_roll;
bool locked_pitch;
float locked_roll_err;
int32_t locked_pitch_cd;
Quaternion q;
bool roll_active_last;
bool pitch_active_last;
bool yaw_active_last;
} acro_state;
bool _enter() override;
};
class ModeAuto : public Mode
{
public:
Number mode_number() const override { return Number::AUTO; }
const char *name() const override { return "AUTO"; }
const char *name4() const override { return "AUTO"; }
bool does_automatic_thermal_switch() const override { return true; }
// methods that affect movement of the vehicle in this mode
void update() override;
void navigate() override;
bool allows_throttle_nudging() const override { return true; }
bool does_auto_navigation() const override;
bool does_auto_throttle() const override;
bool mode_allows_autotuning() const override { return true; }
bool is_landing() const override;
protected:
bool _enter() override;
void _exit() override;
bool _pre_arm_checks(size_t buflen, char *buffer) const override;
};
class ModeAutoTune : public Mode
{
public:
Number mode_number() const override { return Number::AUTOTUNE; }
const char *name() const override { return "AUTOTUNE"; }
const char *name4() const override { return "ATUN"; }
// methods that affect movement of the vehicle in this mode
void update() override;
bool mode_allows_autotuning() const override { return true; }
protected:
bool _enter() override;
};
class ModeGuided : public Mode
{
public:
Number mode_number() const override { return Number::GUIDED; }
const char *name() const override { return "GUIDED"; }
const char *name4() const override { return "GUID"; }
// methods that affect movement of the vehicle in this mode
void update() override;
void navigate() override;
virtual bool is_guided_mode() const override { return true; }
bool allows_throttle_nudging() const override { return true; }
bool does_auto_navigation() const override { return true; }
bool does_auto_throttle() const override { return true; }
// handle a guided target request from GCS
bool handle_guided_request(Location target_loc) override;
void set_radius_and_direction(const float radius, const bool direction_is_ccw);
void update_target_altitude() override;
protected:
bool _enter() override;
bool _pre_arm_checks(size_t buflen, char *buffer) const override { return true; }
private:
float active_radius_m;
};
class ModeCircle: public Mode
{
public:
Number mode_number() const override { return Number::CIRCLE; }
const char *name() const override { return "CIRCLE"; }
const char *name4() const override { return "CIRC"; }
// methods that affect movement of the vehicle in this mode
void update() override;
bool does_auto_navigation() const override { return true; }
bool does_auto_throttle() const override { return true; }
protected:
bool _enter() override;
};
class ModeLoiter : public Mode
{
public:
Number mode_number() const override { return Number::LOITER; }
const char *name() const override { return "LOITER"; }
const char *name4() const override { return "LOIT"; }
// methods that affect movement of the vehicle in this mode
void update() override;
void navigate() override;
bool isHeadingLinedUp(const Location loiterCenterLoc, const Location targetLoc);
bool isHeadingLinedUp_cd(const int32_t bearing_cd);
bool allows_throttle_nudging() const override { return true; }
bool does_auto_navigation() const override { return true; }
bool does_auto_throttle() const override { return true; }
bool allows_terrain_disable() const override { return true; }
void update_target_altitude() override;
bool mode_allows_autotuning() const override { return true; }
protected:
bool _enter() override;
};
#if HAL_QUADPLANE_ENABLED
class ModeLoiterAltQLand : public ModeLoiter
{
public:
Number mode_number() const override { return Number::LOITER_ALT_QLAND; }
const char *name() const override { return "Loiter to QLAND"; }
const char *name4() const override { return "L2QL"; }
// handle a guided target request from GCS
bool handle_guided_request(Location target_loc) override;
protected:
bool _enter() override;
void navigate() override;
private:
void switch_qland();
};
#endif // HAL_QUADPLANE_ENABLED
class ModeManual : public Mode
{
public:
Number mode_number() const override { return Number::MANUAL; }
const char *name() const override { return "MANUAL"; }
const char *name4() const override { return "MANU"; }
// methods that affect movement of the vehicle in this mode
void update() override;
void run() override;
};
class ModeRTL : public Mode
{
public:
Number mode_number() const override { return Number::RTL; }
const char *name() const override { return "RTL"; }
const char *name4() const override { return "RTL "; }
// methods that affect movement of the vehicle in this mode
void update() override;
void navigate() override;
bool allows_throttle_nudging() const override { return true; }
bool does_auto_navigation() const override { return true; }
bool does_auto_throttle() const override { return true; }
protected:
bool _enter() override;
bool _pre_arm_checks(size_t buflen, char *buffer) const override { return false; }
private:
// Switch to QRTL if enabled and within radius
bool switch_QRTL();
};
class ModeStabilize : public Mode
{
public:
Number mode_number() const override { return Number::STABILIZE; }
const char *name() const override { return "STABILIZE"; }
const char *name4() const override { return "STAB"; }
// methods that affect movement of the vehicle in this mode
void update() override;
void run() override;
private:
void stabilize_stick_mixing_direct();
};
class ModeTraining : public Mode
{
public:
Number mode_number() const override { return Number::TRAINING; }
const char *name() const override { return "TRAINING"; }
const char *name4() const override { return "TRAN"; }
// methods that affect movement of the vehicle in this mode
void update() override;
void run() override;
};
class ModeInitializing : public Mode
{
public:
Number mode_number() const override { return Number::INITIALISING; }
const char *name() const override { return "INITIALISING"; }
const char *name4() const override { return "INIT"; }
bool _enter() override { return false; }
// methods that affect movement of the vehicle in this mode
void update() override { }
bool allows_throttle_nudging() const override { return true; }
bool does_auto_throttle() const override { return true; }
protected:
bool _pre_arm_checks(size_t buflen, char *buffer) const override { return false; }
};
class ModeFBWA : public Mode
{
public:
Number mode_number() const override { return Number::FLY_BY_WIRE_A; }
const char *name() const override { return "FLY_BY_WIRE_A"; }
const char *name4() const override { return "FBWA"; }
// methods that affect movement of the vehicle in this mode
void update() override;
bool mode_allows_autotuning() const override { return true; }
};
class ModeFBWB : public Mode
{
public:
Number mode_number() const override { return Number::FLY_BY_WIRE_B; }
const char *name() const override { return "FLY_BY_WIRE_B"; }
const char *name4() const override { return "FBWB"; }
bool allows_terrain_disable() const override { return true; }
bool does_automatic_thermal_switch() const override { return true; }
// methods that affect movement of the vehicle in this mode
void update() override;
bool does_auto_throttle() const override { return true; }
bool mode_allows_autotuning() const override { return true; }
void update_target_altitude() override {};
protected:
bool _enter() override;
};
class ModeCruise : public Mode
{
public:
Number mode_number() const override { return Number::CRUISE; }
const char *name() const override { return "CRUISE"; }
const char *name4() const override { return "CRUS"; }
bool allows_terrain_disable() const override { return true; }
bool does_automatic_thermal_switch() const override { return true; }
// methods that affect movement of the vehicle in this mode
void update() override;
void navigate() override;
bool get_target_heading_cd(int32_t &target_heading) const;
bool does_auto_throttle() const override { return true; }
void update_target_altitude() override {};
protected:
bool _enter() override;
bool locked_heading;
int32_t locked_heading_cd;
uint32_t lock_timer_ms;
};
#if HAL_ADSB_ENABLED
class ModeAvoidADSB : public Mode
{
public:
Number mode_number() const override { return Number::AVOID_ADSB; }
const char *name() const override { return "AVOID_ADSB"; }
const char *name4() const override { return "AVOI"; }
// methods that affect movement of the vehicle in this mode
void update() override;
void navigate() override;
virtual bool is_guided_mode() const override { return true; }
bool does_auto_throttle() const override { return true; }
protected:
bool _enter() override;
};
#endif
#if HAL_QUADPLANE_ENABLED
class ModeQStabilize : public Mode
{
public:
Number mode_number() const override { return Number::QSTABILIZE; }
const char *name() const override { return "QSTABILIZE"; }
const char *name4() const override { return "QSTB"; }
bool is_vtol_mode() const override { return true; }
bool is_vtol_man_throttle() const override { return true; }
virtual bool is_vtol_man_mode() const override { return true; }
bool allows_throttle_nudging() const override { return true; }
// methods that affect movement of the vehicle in this mode
void update() override;
// used as a base class for all Q modes
bool _enter() override;
void run() override;
protected:
private:
void set_tailsitter_roll_pitch(const float roll_input, const float pitch_input);
void set_limited_roll_pitch(const float roll_input, const float pitch_input);
};
class ModeQHover : public Mode
{
public:
Number mode_number() const override { return Number::QHOVER; }
const char *name() const override { return "QHOVER"; }
const char *name4() const override { return "QHOV"; }
bool is_vtol_mode() const override { return true; }
virtual bool is_vtol_man_mode() const override { return true; }
// methods that affect movement of the vehicle in this mode
void update() override;
void run() override;
protected:
bool _enter() override;
};
class ModeQLoiter : public Mode
{
friend class QuadPlane;
friend class ModeQLand;
public:
Number mode_number() const override { return Number::QLOITER; }
const char *name() const override { return "QLOITER"; }
const char *name4() const override { return "QLOT"; }
bool is_vtol_mode() const override { return true; }
virtual bool is_vtol_man_mode() const override { return true; }
// methods that affect movement of the vehicle in this mode
void update() override;
void run() override;
protected:
bool _enter() override;
};
class ModeQLand : public Mode
{
public:
Number mode_number() const override { return Number::QLAND; }
const char *name() const override { return "QLAND"; }
const char *name4() const override { return "QLND"; }
bool is_vtol_mode() const override { return true; }
// methods that affect movement of the vehicle in this mode
void update() override;
void run() override;
protected:
bool _enter() override;
bool _pre_arm_checks(size_t buflen, char *buffer) const override { return false; }
};
class ModeQRTL : public Mode
{
public:
Number mode_number() const override { return Number::QRTL; }
const char *name() const override { return "QRTL"; }
const char *name4() const override { return "QRTL"; }
bool is_vtol_mode() const override { return true; }
// methods that affect movement of the vehicle in this mode
void update() override;
void run() override;
bool does_auto_throttle() const override { return true; }
void update_target_altitude() override;
bool allows_throttle_nudging() const override;
float get_VTOL_return_radius() const;
protected:
bool _enter() override;
bool _pre_arm_checks(size_t buflen, char *buffer) const override { return false; }
private:
enum class SubMode {
climb,
RTL,
} submode;
};
class ModeQAcro : public Mode
{
public:
Number mode_number() const override { return Number::QACRO; }
const char *name() const override { return "QACRO"; }
const char *name4() const override { return "QACO"; }
bool is_vtol_mode() const override { return true; }
bool is_vtol_man_throttle() const override { return true; }
virtual bool is_vtol_man_mode() const override { return true; }
// methods that affect movement of the vehicle in this mode
void update() override;
void run() override;
protected:
bool _enter() override;
};
#if QAUTOTUNE_ENABLED
class ModeQAutotune : public Mode
{
public:
Number mode_number() const override { return Number::QAUTOTUNE; }
const char *name() const override { return "QAUTOTUNE"; }
const char *name4() const override { return "QATN"; }
bool is_vtol_mode() const override { return true; }
virtual bool is_vtol_man_mode() const override { return true; }
void run() override;
// methods that affect movement of the vehicle in this mode
void update() override;
protected:
bool _enter() override;
void _exit() override;
};
#endif // QAUTOTUNE_ENABLED
#endif // HAL_QUADPLANE_ENABLED
class ModeTakeoff: public Mode
{
public:
ModeTakeoff();
Number mode_number() const override { return Number::TAKEOFF; }
const char *name() const override { return "TAKEOFF"; }
const char *name4() const override { return "TKOF"; }
// methods that affect movement of the vehicle in this mode
void update() override;
void navigate() override;
bool allows_throttle_nudging() const override { return true; }
bool does_auto_navigation() const override { return true; }
bool does_auto_throttle() const override { return true; }
// var_info for holding parameter information
static const struct AP_Param::GroupInfo var_info[];
AP_Int16 target_alt;
AP_Int16 level_alt;
AP_Float ground_pitch;
protected:
AP_Int16 target_dist;
AP_Int8 level_pitch;
bool takeoff_started;
Location start_loc;
bool _enter() override;
};
#if HAL_SOARING_ENABLED
class ModeThermal: public Mode
{
public:
Number mode_number() const override { return Number::THERMAL; }
const char *name() const override { return "THERMAL"; }
const char *name4() const override { return "THML"; }
// methods that affect movement of the vehicle in this mode
void update() override;
// Update thermal tracking and exiting logic.
void update_soaring();
void navigate() override;
bool allows_throttle_nudging() const override { return true; }
bool does_auto_navigation() const override { return true; }
// true if we are in an auto-throttle mode, which means
// we need to run the speed/height controller
bool does_auto_throttle() const override { return true; }
protected:
bool exit_heading_aligned() const;
void restore_mode(const char *reason, ModeReason modereason);
bool _enter() override;
};
#endif