Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduSub/mode.h
9594 views
1
#pragma once
2
3
#include "Sub.h"
4
class Parameters;
5
class ParametersG2;
6
7
class GCS_Sub;
8
9
// Guided modes
10
enum GuidedSubMode {
11
Guided_WP,
12
Guided_Velocity,
13
Guided_PosVel,
14
Guided_Angle,
15
};
16
17
// Auto modes
18
enum AutoSubMode {
19
Auto_WP,
20
Auto_CircleMoveToEdge,
21
Auto_Circle,
22
Auto_NavGuided,
23
Auto_Loiter,
24
Auto_TerrainRecover
25
};
26
27
// RTL states
28
enum RTLState {
29
RTL_InitialClimb,
30
RTL_ReturnHome,
31
RTL_LoiterAtHome,
32
RTL_FinalDescent,
33
RTL_Land
34
};
35
36
class Mode
37
{
38
39
public:
40
41
// Auto Pilot Modes enumeration
42
enum class Number : uint8_t {
43
STABILIZE = 0, // manual angle with manual depth/throttle
44
ACRO = 1, // manual body-frame angular rate with manual depth/throttle
45
ALT_HOLD = 2, // manual angle with automatic depth/throttle
46
AUTO = 3, // fully automatic waypoint control using mission commands
47
GUIDED = 4, // fully automatic fly to coordinate or fly at velocity/direction using GCS immediate commands
48
CIRCLE = 7, // automatic circular flight with automatic throttle
49
SURFACE = 9, // automatically return to surface, pilot maintains horizontal control
50
POSHOLD = 16, // automatic position hold with manual override, with automatic throttle
51
MANUAL = 19, // Pass-through input with no stabilization
52
MOTOR_DETECT = 20, // Automatically detect motors orientation
53
SURFTRAK = 21 // Track distance above seafloor (hold range)
54
// Mode number 30 reserved for "offboard" for external/lua control.
55
};
56
57
// constructor
58
Mode(void);
59
60
// do not allow copying
61
CLASS_NO_COPY(Mode);
62
63
// child classes should override these methods
64
virtual bool init(bool ignore_checks) { return true; }
65
virtual void run() = 0;
66
virtual bool requires_GPS() const = 0;
67
virtual bool requires_altitude() const = 0;
68
virtual bool allows_arming(bool from_gcs) const = 0;
69
virtual bool is_autopilot() const { return false; }
70
virtual bool in_guided_mode() const { return false; }
71
72
// return a string for this flightmode
73
virtual const char *name() const = 0;
74
virtual const char *name4() const = 0;
75
76
// returns a unique number specific to this mode
77
virtual Mode::Number number() const = 0;
78
79
// pilot input processing
80
void get_pilot_desired_angle_rates(int16_t roll_in, int16_t pitch_in, int16_t yaw_in, float &roll_out, float &pitch_out, float &yaw_out);
81
82
83
protected:
84
85
// navigation support functions
86
virtual void run_autopilot() {}
87
88
// helper functions
89
bool is_disarmed_or_landed() const;
90
91
// functions to control landing
92
// in modes that support landing
93
void land_run_horizontal_control();
94
void land_run_vertical_control(bool pause_descent = false);
95
96
// convenience references to avoid code churn in conversion:
97
Parameters &g;
98
ParametersG2 &g2;
99
AP_InertialNav &inertial_nav;
100
AP_AHRS &ahrs;
101
AP_Motors6DOF &motors;
102
RC_Channel *&channel_roll;
103
RC_Channel *&channel_pitch;
104
RC_Channel *&channel_throttle;
105
RC_Channel *&channel_yaw;
106
RC_Channel *&channel_forward;
107
RC_Channel *&channel_lateral;
108
AC_PosControl *position_control;
109
AC_AttitudeControl_Sub *attitude_control;
110
// TODO: channels
111
float &G_Dt;
112
113
public:
114
115
// pass-through functions to reduce code churn on conversion;
116
// these are candidates for moving into the Mode base
117
// class.
118
bool set_mode(Mode::Number mode, ModeReason reason);
119
GCS_Sub &gcs();
120
121
// end pass-through functions
122
};
123
124
class ModeManual : public Mode
125
{
126
127
public:
128
// inherit constructor
129
using Mode::Mode;
130
virtual void run() override;
131
bool init(bool ignore_checks) override;
132
bool requires_GPS() const override { return false; }
133
bool requires_altitude() const override { return false; }
134
bool allows_arming(bool from_gcs) const override { return true; }
135
bool is_autopilot() const override { return false; }
136
137
protected:
138
139
const char *name() const override { return "Manual"; }
140
const char *name4() const override { return "MANU"; }
141
Mode::Number number() const override { return Mode::Number::MANUAL; }
142
};
143
144
145
class ModeAcro : public Mode
146
{
147
148
public:
149
// inherit constructor
150
using Mode::Mode;
151
152
virtual void run() override;
153
154
bool init(bool ignore_checks) override;
155
bool requires_GPS() const override { return false; }
156
bool requires_altitude() const override { return false; }
157
bool allows_arming(bool from_gcs) const override { return true; }
158
bool is_autopilot() const override { return false; }
159
160
protected:
161
162
const char *name() const override { return "Acro"; }
163
const char *name4() const override { return "ACRO"; }
164
Mode::Number number() const override { return Mode::Number::ACRO; }
165
};
166
167
168
class ModeStabilize : public Mode
169
{
170
171
public:
172
// inherit constructor
173
using Mode::Mode;
174
175
virtual void run() override;
176
177
bool init(bool ignore_checks) override;
178
bool requires_GPS() const override { return false; }
179
bool requires_altitude() const override { return false; }
180
bool allows_arming(bool from_gcs) const override { return true; }
181
bool is_autopilot() const override { return false; }
182
183
protected:
184
185
const char *name() const override { return "Stabilize"; }
186
const char *name4() const override { return "STAB"; }
187
Mode::Number number() const override { return Mode::Number::STABILIZE; }
188
};
189
190
191
class ModeAlthold : public Mode
192
{
193
194
public:
195
// inherit constructor
196
using Mode::Mode;
197
198
virtual void run() override;
199
200
bool init(bool ignore_checks) override;
201
bool requires_GPS() const override { return false; }
202
bool requires_altitude() const override { return true; }
203
bool allows_arming(bool from_gcs) const override { return true; }
204
bool is_autopilot() const override { return false; }
205
void control_depth();
206
207
protected:
208
209
void run_pre();
210
void run_post();
211
212
const char *name() const override { return "Depth Hold"; }
213
const char *name4() const override { return "ALTH"; }
214
Mode::Number number() const override { return Mode::Number::ALT_HOLD; }
215
};
216
217
218
class ModeSurftrak : public ModeAlthold
219
{
220
221
public:
222
// constructor
223
ModeSurftrak();
224
225
void run() override;
226
227
bool init(bool ignore_checks) override;
228
229
float get_rangefinder_target_cm() const WARN_IF_UNUSED { return rangefinder_target_cm; }
230
bool set_rangefinder_target_cm(float target_cm);
231
232
protected:
233
234
const char *name() const override { return "Surftrak"; }
235
const char *name4() const override { return "STRK"; }
236
Mode::Number number() const override { return Mode::Number::SURFTRAK; }
237
238
private:
239
240
void reset();
241
void control_range();
242
void update_surface_offset();
243
244
float rangefinder_target_cm;
245
246
bool pilot_in_control; // pilot is moving up/down
247
float pilot_control_start_z_cm; // alt when pilot took control
248
};
249
250
class ModeGuided : public Mode
251
{
252
253
public:
254
// inherit constructor
255
using Mode::Mode;
256
257
virtual void run() override;
258
259
bool init(bool ignore_checks) override;
260
bool requires_GPS() const override { return true; }
261
bool requires_altitude() const override { return true; }
262
bool allows_arming(bool from_gcs) const override { return true; }
263
bool is_autopilot() const override { return true; }
264
bool in_guided_mode() const override { return true; }
265
bool guided_limit_check();
266
void guided_limit_init_time_and_pos();
267
void guided_set_angle(const Quaternion &q, float climb_rate_cms, bool use_yaw_rate, float yaw_rate_rads);
268
void guided_set_angle(const Quaternion&, float);
269
void guided_limit_set(uint32_t timeout_ms, float alt_min_cm, float alt_max_cm, float horiz_max_cm);
270
bool guided_set_destination_posvel(const Vector3f& destination, const Vector3f& velocity);
271
bool guided_set_destination_posvel(const Vector3f& destination, const Vector3f& velocity, bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_yaw);
272
bool guided_set_destination(const Vector3f& destination);
273
bool guided_set_destination(const Location&);
274
bool guided_set_destination(const Vector3f& destination, bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_yaw);
275
void guided_set_velocity(const Vector3f& velocity);
276
void guided_set_velocity(const Vector3f& velocity, bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_yaw);
277
void guided_set_yaw_state(bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_angle);
278
float get_auto_heading();
279
void guided_limit_clear();
280
void set_auto_yaw_mode(autopilot_yaw_mode yaw_mode);
281
282
protected:
283
284
const char *name() const override { return "Guided"; }
285
const char *name4() const override { return "GUID"; }
286
Mode::Number number() const override { return Mode::Number::GUIDED; }
287
288
autopilot_yaw_mode get_default_auto_yaw_mode(bool rtl) const;
289
290
private:
291
void guided_pos_control_run();
292
void guided_vel_control_run();
293
void guided_posvel_control_run();
294
void guided_angle_control_run();
295
void guided_takeoff_run();
296
void guided_pos_control_start();
297
void guided_vel_control_start();
298
void guided_posvel_control_start();
299
void guided_angle_control_start();
300
};
301
302
303
304
class ModeAuto : public ModeGuided
305
{
306
307
public:
308
// inherit constructor
309
using ModeGuided::ModeGuided;
310
311
virtual void run() override;
312
313
bool init(bool ignore_checks) override;
314
bool requires_GPS() const override { return true; }
315
bool requires_altitude() const override { return true; }
316
bool allows_arming(bool from_gcs) const override { return true; }
317
bool is_autopilot() const override { return true; }
318
bool auto_loiter_start();
319
void auto_wp_start(const Vector3f& destination);
320
void auto_wp_start(const Location& dest_loc);
321
void auto_circle_movetoedge_start(const Location &circle_center, float radius_m, bool ccw_turn);
322
void auto_circle_start();
323
void auto_nav_guided_start();
324
void set_auto_yaw_roi(const Location &roi_location);
325
void set_auto_yaw_look_at_heading(float angle_deg, float turn_rate_dps, int8_t direction, uint8_t relative_angle);
326
void set_yaw_rate(float turn_rate_dps);
327
bool auto_terrain_recover_start();
328
329
protected:
330
331
const char *name() const override { return "Auto"; }
332
const char *name4() const override { return "AUTO"; }
333
Mode::Number number() const override { return Mode::Number::AUTO; }
334
335
private:
336
void auto_wp_run();
337
void auto_circle_run();
338
void auto_nav_guided_run();
339
void auto_loiter_run();
340
void auto_terrain_recover_run();
341
};
342
343
344
class ModePoshold : public ModeAlthold
345
{
346
347
public:
348
// inherit constructor
349
using ModeAlthold::ModeAlthold;
350
351
virtual void run() override;
352
353
bool init(bool ignore_checks) override;
354
355
bool requires_GPS() const override { return true; }
356
bool requires_altitude() const override { return true; }
357
bool allows_arming(bool from_gcs) const override { return true; }
358
bool is_autopilot() const override { return true; }
359
360
protected:
361
362
const char *name() const override { return "Position Hold"; }
363
const char *name4() const override { return "POSH"; }
364
Mode::Number number() const override { return Mode::Number::POSHOLD; }
365
366
private:
367
368
void control_horizontal();
369
};
370
371
372
class ModeCircle : public Mode
373
{
374
375
public:
376
// inherit constructor
377
using Mode::Mode;
378
379
virtual void run() override;
380
381
bool init(bool ignore_checks) override;
382
bool requires_GPS() const override { return true; }
383
bool requires_altitude() const override { return true; }
384
bool allows_arming(bool from_gcs) const override { return true; }
385
bool is_autopilot() const override { return true; }
386
387
protected:
388
389
const char *name() const override { return "Circle"; }
390
const char *name4() const override { return "CIRC"; }
391
Mode::Number number() const override { return Mode::Number::CIRCLE; }
392
};
393
394
class ModeSurface : public Mode
395
{
396
397
public:
398
// inherit constructor
399
using Mode::Mode;
400
401
virtual void run() override;
402
403
bool init(bool ignore_checks) override;
404
bool requires_GPS() const override { return false; }
405
bool requires_altitude() const override { return false; }
406
bool allows_arming(bool from_gcs) const override { return true; }
407
bool is_autopilot() const override { return true; }
408
409
protected:
410
const char *name() const override { return "Surface"; }
411
const char *name4() const override { return "SURF"; }
412
Mode::Number number() const override { return Mode::Number::SURFACE; }
413
bool nobaro_mode;
414
};
415
416
417
class ModeMotordetect : public Mode
418
{
419
420
public:
421
// inherit constructor
422
using Mode::Mode;
423
424
virtual void run() override;
425
426
bool init(bool ignore_checks) override;
427
bool requires_GPS() const override { return false; }
428
bool requires_altitude() const override { return false; }
429
bool allows_arming(bool from_gcs) const override { return true; }
430
bool is_autopilot() const override { return true; }
431
432
protected:
433
434
const char *name() const override { return "Motor Detection"; }
435
const char *name4() const override { return "DETE"; }
436
Mode::Number number() const override { return Mode::Number::MOTOR_DETECT; }
437
};
438
439