Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduSub/Sub.h
9563 views
1
/*
2
This program is free software: you can redistribute it and/or modify
3
it under the terms of the GNU General Public License as published by
4
the Free Software Foundation, either version 3 of the License, or
5
(at your option) any later version.
6
7
This program is distributed in the hope that it will be useful,
8
but WITHOUT ANY WARRANTY; without even the implied warranty of
9
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10
GNU General Public License for more details.
11
12
You should have received a copy of the GNU General Public License
13
along with this program. If not, see <http://www.gnu.org/licenses/>.
14
*/
15
#pragma once
16
/*
17
This is the main Sub class
18
*/
19
20
////////////////////////////////////////////////////////////////////////////////
21
// Header includes
22
////////////////////////////////////////////////////////////////////////////////
23
24
#include <cmath>
25
#include <stdio.h>
26
#include <stdarg.h>
27
28
#include <AP_HAL/AP_HAL.h>
29
30
// Common dependencies
31
#include <AP_Common/AP_Common.h>
32
#include <AP_Common/Location.h>
33
#include <AP_Param/AP_Param.h>
34
#include <StorageManager/StorageManager.h>
35
#include <AP_AccelCal/AP_AccelCal.h> // interface and maths for accelerometer calibration
36
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
37
#include <AP_Declination/AP_Declination.h> // ArduPilot Mega Declination Helper Library
38
39
// Application dependencies
40
#include <AP_GPS/AP_GPS.h> // ArduPilot GPS library
41
#include <AP_Logger/AP_Logger.h> // ArduPilot Mega Flash Memory Library
42
#include <AP_Baro/AP_Baro.h>
43
#include <AP_Compass/AP_Compass.h> // ArduPilot Mega Magnetometer Library
44
#include <AP_InertialSensor/AP_InertialSensor.h> // ArduPilot Mega Inertial Sensor (accel & gyro) Library
45
#include <AP_AHRS/AP_AHRS.h>
46
#include <AP_Mission/AP_Mission.h> // Mission command library
47
#include <AC_AttitudeControl/AC_AttitudeControl_Sub.h> // Attitude control library
48
#include <AC_AttitudeControl/AC_PosControl.h> // Position control library
49
#include <AP_Motors/AP_Motors.h> // AP Motors library
50
#include <Filter/Filter.h> // Filter library
51
#include <AP_Relay/AP_Relay.h> // APM relay
52
#include <AP_Mount/AP_Mount.h> // Camera/Antenna mount
53
#include <AP_Vehicle/AP_Vehicle.h> // needed for AHRS build
54
#include <AP_InertialNav/AP_InertialNav.h> // inertial navigation library
55
#include <AC_WPNav/AC_WPNav.h> // Waypoint navigation library
56
#include <AC_WPNav/AC_Loiter.h>
57
#include <AC_WPNav/AC_Circle.h> // circle navigation library
58
#include <AP_Scheduler/AP_Scheduler.h> // main loop scheduler
59
#include <AP_Scheduler/PerfInfo.h> // loop perf monitoring
60
#include <AP_BattMonitor/AP_BattMonitor.h> // Battery monitor library
61
#include <AP_Terrain/AP_Terrain.h>
62
#include <AP_JSButton/AP_JSButton.h> // Joystick/gamepad button function assignment
63
#include <AP_LeakDetector/AP_LeakDetector.h> // Leak detector
64
#include <AP_Proximity/AP_Proximity.h>
65
#include <AP_Rally/AP_Rally.h>
66
#include <AP_OSD/AP_OSD.h>
67
68
// Local modules
69
#include "defines.h"
70
#include "config.h"
71
#include "GCS_MAVLink_Sub.h"
72
#include "RC_Channel_Sub.h" // RC Channel Library
73
#include "Parameters.h"
74
#include "AP_Arming_Sub.h"
75
#include "GCS_Sub.h"
76
#include "mode.h"
77
#include "script_button.h"
78
79
80
#include <AP_OpticalFlow/AP_OpticalFlow.h> // Optical Flow library
81
82
// libraries which are dependent on #defines in defines.h and/or config.h
83
#if RCMAP_ENABLED
84
#include <AP_RCMapper/AP_RCMapper.h> // RC input mapping library
85
#endif
86
87
#include <AP_RPM/AP_RPM_config.h>
88
89
#if AP_RPM_ENABLED
90
#include <AP_RPM/AP_RPM.h>
91
#endif
92
93
#if AVOIDANCE_ENABLED
94
#include <AC_Avoidance/AC_Avoid.h> // Stop at fence library
95
#endif
96
97
#include <AP_Camera/AP_Camera.h> // Photo or video camera
98
99
#if AP_SCRIPTING_ENABLED
100
#include <AP_Scripting/AP_Scripting.h>
101
#endif
102
103
class Sub : public AP_Vehicle {
104
public:
105
friend class GCS_MAVLINK_Sub;
106
friend class GCS_Sub;
107
friend class Parameters;
108
friend class ParametersG2;
109
friend class AP_Arming_Sub;
110
friend class RC_Channels_Sub;
111
friend class RC_Channel_Sub;
112
friend class Mode;
113
friend class ModeManual;
114
friend class ModeStabilize;
115
friend class ModeAcro;
116
friend class ModeAlthold;
117
friend class ModeSurftrak;
118
friend class ModeGuided;
119
friend class ModePoshold;
120
friend class ModeAuto;
121
friend class ModeCircle;
122
friend class ModeSurface;
123
friend class ModeMotordetect;
124
125
Sub(void);
126
127
protected:
128
129
bool should_zero_rc_outputs_on_reboot() const override { return true; }
130
131
private:
132
133
// Global parameters are all contained within the 'g' class.
134
Parameters g;
135
ParametersG2 g2;
136
137
// primary input control channels
138
RC_Channel *channel_roll;
139
RC_Channel *channel_pitch;
140
RC_Channel *channel_throttle;
141
RC_Channel *channel_yaw;
142
RC_Channel *channel_forward;
143
RC_Channel *channel_lateral;
144
145
#if AP_SUB_RC_ENABLED
146
// flight modes convenience array
147
AP_Int8 *flight_modes;
148
const uint8_t num_flight_modes = 6;
149
#endif
150
151
AP_LeakDetector leak_detector;
152
153
struct {
154
bool enabled;
155
bool alt_healthy; // true if we can trust the altitude from the rangefinder
156
float alt; // tilt compensated altitude from rangefinder
157
float min; // min rangefinder distance
158
float max; // max rangefinder distance
159
uint32_t last_healthy_ms;
160
float inertial_alt_cm; // inertial alt at time of last rangefinder sample
161
float rangefinder_terrain_offset_cm; // terrain height above EKF origin
162
LowPassFilterFloat alt_filt; // altitude filter
163
} rangefinder_state = { false, false, 0, 0, 0, 0, 0, 0 };
164
165
// Mission library
166
AP_Mission mission{
167
FUNCTOR_BIND_MEMBER(&Sub::start_command, bool, const AP_Mission::Mission_Command &),
168
FUNCTOR_BIND_MEMBER(&Sub::verify_command_callback, bool, const AP_Mission::Mission_Command &),
169
FUNCTOR_BIND_MEMBER(&Sub::exit_mission, void)};
170
171
// Optical flow sensor
172
#if AP_OPTICALFLOW_ENABLED
173
AP_OpticalFlow optflow;
174
#endif
175
176
#if OSD_ENABLED || OSD_PARAM_ENABLED
177
AP_OSD osd;
178
#endif
179
180
// system time in milliseconds of last recorded yaw reset from ekf
181
uint32_t ekfYawReset_ms = 0;
182
183
// GCS selection
184
GCS_Sub _gcs; // avoid using this; use gcs()
185
GCS_Sub &gcs() { return _gcs; }
186
187
// User variables
188
#ifdef USERHOOK_VARIABLES
189
# include USERHOOK_VARIABLES
190
#endif
191
192
// Documentation of Globals:
193
union {
194
struct {
195
uint8_t pre_arm_check : 1; // true if all pre-arm checks (rc, accel calibration, gps lock) have been performed
196
uint8_t logging_started : 1; // true if logging has started
197
uint8_t compass_mot : 1; // true if we are currently performing compassmot calibration
198
uint8_t motor_test : 1; // true if we are currently performing the motors test
199
uint8_t initialised : 1; // true once the init_ardupilot function has completed. Extended status to GCS is not sent until this completes
200
uint8_t gps_base_pos_set : 1; // true when the gps base position has been set (used for RTK gps only)
201
uint8_t at_bottom : 1; // true if we are at the bottom
202
uint8_t at_surface : 1; // true if we are at the surface
203
uint8_t depth_sensor_present: 1; // true if there is a depth sensor detected at boot
204
uint8_t unused1 : 1; // was compass_init_location; true when the compass's initial location has been set
205
};
206
uint32_t value;
207
} ap;
208
209
// This is the state of the flight control system
210
// There are multiple states defined such as STABILIZE, ACRO,
211
Mode::Number control_mode;
212
213
Mode::Number prev_control_mode;
214
215
#if RCMAP_ENABLED
216
RCMapper rcmap;
217
#endif
218
219
// Failsafe
220
struct {
221
uint32_t last_leak_warn_ms; // last time a leak warning was sent to gcs
222
uint32_t last_gcs_warn_ms;
223
uint32_t last_pilot_input_ms; // last time we received pilot input in the form of MANUAL_CONTROL or RC_CHANNELS_OVERRIDE messages
224
uint32_t terrain_first_failure_ms; // the first time terrain data access failed - used to calculate the duration of the failure
225
uint32_t terrain_last_failure_ms; // the most recent time terrain data access failed
226
uint32_t last_crash_warn_ms; // last time a crash warning was sent to gcs
227
uint32_t last_ekf_warn_ms; // last time an ekf warning was sent to gcs
228
#if AP_SUB_RC_ENABLED
229
int8_t radio_counter; // number of iterations with throttle below throttle_fs_value
230
uint8_t radio : 1; // A status flag for the radio failsafe
231
#endif
232
233
uint8_t pilot_input : 1; // true if pilot input failsafe is active, handles things like joystick being disconnected during operation
234
uint8_t gcs : 1; // A status flag for the ground station failsafe
235
uint8_t ekf : 1; // true if ekf failsafe has occurred
236
uint8_t terrain : 1; // true if the missing terrain data failsafe has occurred
237
uint8_t leak : 1; // true if leak recently detected
238
uint8_t internal_pressure : 1; // true if internal pressure is over threshold
239
uint8_t internal_temperature : 1; // true if temperature is over threshold
240
uint8_t crash : 1; // true if we are crashed
241
uint8_t sensor_health : 1; // true if at least one sensor has triggered a failsafe (currently only used for depth in depth enabled modes)
242
} failsafe;
243
244
bool any_failsafe_triggered() const {
245
return (
246
failsafe.pilot_input
247
|| battery.has_failsafed()
248
|| failsafe.gcs
249
|| failsafe.ekf
250
|| failsafe.terrain
251
|| failsafe.leak
252
|| failsafe.internal_pressure
253
|| failsafe.internal_temperature
254
|| failsafe.crash
255
|| failsafe.sensor_health
256
);
257
}
258
259
// sensor health for logging
260
struct {
261
uint8_t depth : 1; // true if depth sensor is healthy
262
uint8_t compass : 1; // true if compass is healthy
263
} sensor_health;
264
265
// Baro sensor instance index of the external water pressure sensor
266
uint8_t depth_sensor_idx;
267
268
AP_Motors6DOF motors;
269
270
// Circle
271
bool circle_pilot_yaw_override; // true if pilot is overriding yaw
272
273
// Stores initial bearing when armed
274
int32_t initial_armed_bearing;
275
276
// Loiter control
277
uint16_t loiter_time_max; // How long we should stay in Loiter Mode for mission scripting (time in seconds)
278
uint32_t loiter_time; // How long have we been loitering - The start time in millis
279
280
// Delay the next navigation command
281
uint32_t nav_delay_time_max_ms; // used for delaying the navigation commands
282
uint32_t nav_delay_time_start_ms;
283
284
// Battery Sensors
285
AP_BattMonitor battery{MASK_LOG_CURRENT,
286
FUNCTOR_BIND_MEMBER(&Sub::handle_battery_failsafe, void, const char*, const int8_t),
287
_failsafe_priorities};
288
289
AP_Arming_Sub arming;
290
291
// Altitude
292
// The cm/s we are moving up or down based on filtered data - Positive = UP
293
int16_t climb_rate;
294
295
// Turn counter
296
int32_t quarter_turn_count;
297
uint8_t last_turn_state;
298
299
// Input gain
300
float gain;
301
302
// Flag indicating if we are currently using input hold
303
bool input_hold_engaged;
304
305
// Flag indicating if we are currently controlling Pitch and Roll instead of forward/lateral
306
bool roll_pitch_flag = false;
307
308
// 3D Location vectors
309
// Current location of the Sub (altitude is relative to home)
310
Location current_loc;
311
312
// Navigation Yaw control
313
// auto flight mode's yaw mode
314
uint8_t auto_yaw_mode;
315
316
// Parameter to set yaw rate only
317
bool yaw_rate_only;
318
319
// Yaw will point at this location if auto_yaw_mode is set to AUTO_YAW_ROI
320
Vector3f roi_WP;
321
322
// bearing from current location to the yaw_look_at_WP
323
float yaw_look_at_WP_bearing;
324
325
float yaw_xtrack_correct_heading;
326
327
// yaw used for YAW_LOOK_AT_HEADING yaw_mode
328
int32_t yaw_look_at_heading;
329
330
// Deg/s we should turn
331
int16_t yaw_look_at_heading_slew;
332
333
// heading when in yaw_look_ahead_bearing
334
float yaw_look_ahead_bearing;
335
336
// Delay Mission Scripting Command
337
int32_t condition_value; // used in condition commands (eg delay, change alt, etc.)
338
uint32_t condition_start;
339
340
// Inertial Navigation
341
AP_InertialNav inertial_nav;
342
343
AP_AHRS_View ahrs_view;
344
345
// Attitude, Position and Waypoint navigation objects
346
// To-Do: move inertial nav up or other navigation variables down here
347
AC_AttitudeControl_Sub attitude_control;
348
349
AC_PosControl pos_control;
350
351
AC_WPNav wp_nav;
352
AC_Loiter loiter_nav;
353
AC_Circle circle_nav;
354
355
// Camera
356
#if AP_CAMERA_ENABLED
357
AP_Camera camera{MASK_LOG_CAMERA};
358
#endif
359
360
// Camera/Antenna mount tracking and stabilisation stuff
361
#if HAL_MOUNT_ENABLED
362
AP_Mount camera_mount;
363
#endif
364
365
#if AVOIDANCE_ENABLED
366
AC_Avoid avoid;
367
#endif
368
369
// Rally library
370
#if HAL_RALLY_ENABLED
371
AP_Rally rally;
372
#endif
373
374
// terrain handling
375
#if AP_TERRAIN_AVAILABLE
376
AP_Terrain terrain;
377
#endif
378
379
// used to allow attitude and depth control without a position system
380
struct attitude_no_gps_struct {
381
uint32_t last_message_ms;
382
mavlink_set_attitude_target_t packet;
383
};
384
385
attitude_no_gps_struct set_attitude_target_no_gps {0};
386
387
// Top-level logic
388
// setup the var_info table
389
AP_Param param_loader;
390
391
float last_pilot_heading_rad;
392
uint32_t last_pilot_yaw_input_ms;
393
uint32_t fs_terrain_recover_start_ms;
394
395
static const AP_Scheduler::Task scheduler_tasks[];
396
static const AP_Param::Info var_info[];
397
static const struct LogStructure log_structure[];
398
399
void run_rate_controller();
400
void fifty_hz_loop();
401
void update_batt_compass(void);
402
void ten_hz_logging_loop();
403
void twentyfive_hz_logging();
404
void loop_rate_logging();
405
void three_hz_loop();
406
void one_hz_loop();
407
void update_turn_counter();
408
void read_AHRS(void);
409
void update_altitude();
410
float get_smoothing_gain();
411
void get_pilot_desired_lean_angles(float roll_in, float pitch_in, float &roll_out, float &pitch_out, float angle_max);
412
float get_pilot_desired_yaw_rate(int16_t stick_angle) const;
413
void check_ekf_yaw_reset();
414
float get_roi_yaw();
415
float get_look_ahead_yaw();
416
float get_pilot_desired_climb_rate(float throttle_control);
417
float get_pilot_desired_horizontal_rate(RC_Channel *channel) const;
418
void rotate_body_frame_to_NE(float &x, float &y);
419
#if HAL_LOGGING_ENABLED
420
// methods for AP_Vehicle:
421
const AP_Int32 &get_log_bitmask() override { return g.log_bitmask; }
422
const struct LogStructure *get_log_structures() const override {
423
return log_structure;
424
}
425
uint8_t get_num_log_structures() const override;
426
427
void Log_Write_Control_Tuning();
428
void Log_Write_Attitude();
429
void Log_Write_Data(LogDataID id, int32_t value);
430
void Log_Write_Data(LogDataID id, uint32_t value);
431
void Log_Write_Data(LogDataID id, int16_t value);
432
void Log_Write_Data(LogDataID id, uint16_t value);
433
void Log_Write_Data(LogDataID id, float value);
434
void Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target, const Vector3f& vel_target);
435
void Log_Write_Vehicle_Startup_Messages();
436
#endif
437
void load_parameters(void) override;
438
void userhook_init();
439
void userhook_FastLoop();
440
void userhook_50Hz();
441
void userhook_MediumLoop();
442
void userhook_SlowLoop();
443
void userhook_SuperSlowLoop();
444
void update_home_from_EKF();
445
bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED;
446
bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED;
447
float get_alt_rel() const WARN_IF_UNUSED;
448
float get_alt_msl() const WARN_IF_UNUSED;
449
void exit_mission();
450
void set_origin(const Location& loc);
451
bool verify_loiter_unlimited();
452
bool verify_loiter_time();
453
bool verify_wait_delay();
454
bool verify_within_distance();
455
bool verify_yaw();
456
457
void failsafe_sensors_check(void);
458
void failsafe_crash_check();
459
void failsafe_ekf_check(void);
460
void handle_battery_failsafe(const char* type_str, const int8_t action);
461
void failsafe_gcs_check();
462
void failsafe_pilot_input_check(void);
463
void set_neutral_controls(void);
464
void failsafe_terrain_check();
465
void failsafe_terrain_set_status(bool data_ok);
466
void failsafe_terrain_on_event();
467
void mainloop_failsafe_enable();
468
void mainloop_failsafe_disable();
469
#if AP_FENCE_ENABLED
470
void fence_check();
471
void fence_checks_async() override;
472
#endif
473
bool set_mode(Mode::Number mode, ModeReason reason);
474
bool set_mode(const uint8_t new_mode, const ModeReason reason) override;
475
uint8_t get_mode() const override { return (uint8_t)control_mode; }
476
void update_flight_mode();
477
void exit_mode(Mode::Number old_control_mode, Mode::Number new_control_mode);
478
void notify_flight_mode();
479
void read_inertia();
480
void update_surface_and_bottom_detector();
481
void set_surfaced(bool at_surface);
482
void set_bottomed(bool at_bottom);
483
void motors_output();
484
void init_rc_in();
485
void init_rc_out();
486
#if AP_SUB_RC_ENABLED
487
void rc_loop();
488
void read_radio();
489
// last valid RC input time
490
uint32_t last_radio_update_ms;
491
void set_failsafe_radio(bool b);
492
void set_throttle_and_failsafe(uint16_t throttle_pwm);
493
void failsafe_radio_off_event();
494
void failsafe_radio_on_event();
495
#endif
496
void enable_motor_output();
497
void init_joystick();
498
void transform_manual_control_to_rc_override(int16_t x, int16_t y, int16_t z, int16_t r, uint16_t buttons, uint16_t buttons2, uint8_t enabled_extensions,
499
int16_t s,
500
int16_t t,
501
int16_t aux1,
502
int16_t aux2,
503
int16_t aux3,
504
int16_t aux4,
505
int16_t aux5,
506
int16_t aux6);
507
void handle_jsbutton_press(uint8_t button,bool shift=false,bool held=false);
508
void handle_jsbutton_release(uint8_t button, bool shift);
509
JSButton* get_button(uint8_t index);
510
void default_js_buttons(void);
511
void clear_input_hold();
512
void read_barometer(void);
513
void init_rangefinder(void);
514
void read_rangefinder(void);
515
void terrain_update();
516
void terrain_logging();
517
void init_ardupilot() override;
518
void get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
519
uint8_t &task_count,
520
uint32_t &log_bit) override;
521
void startup_INS_ground();
522
bool position_ok();
523
bool ekf_position_ok();
524
bool optflow_position_ok();
525
bool should_log(uint32_t mask);
526
bool start_command(const AP_Mission::Mission_Command& cmd);
527
bool verify_command(const AP_Mission::Mission_Command& cmd);
528
bool verify_command_callback(const AP_Mission::Mission_Command& cmd);
529
530
bool do_guided(const AP_Mission::Mission_Command& cmd);
531
void do_nav_wp(const AP_Mission::Mission_Command& cmd);
532
void do_surface(const AP_Mission::Mission_Command& cmd);
533
void do_RTL(void);
534
void do_loiter_unlimited(const AP_Mission::Mission_Command& cmd);
535
void do_circle(const AP_Mission::Mission_Command& cmd);
536
void do_loiter_time(const AP_Mission::Mission_Command& cmd);
537
#if NAV_GUIDED
538
void do_nav_guided_enable(const AP_Mission::Mission_Command& cmd);
539
void do_guided_limits(const AP_Mission::Mission_Command& cmd);
540
#endif
541
void do_nav_delay(const AP_Mission::Mission_Command& cmd);
542
void do_wait_delay(const AP_Mission::Mission_Command& cmd);
543
void do_within_distance(const AP_Mission::Mission_Command& cmd);
544
void do_yaw(const AP_Mission::Mission_Command& cmd);
545
void do_change_speed(const AP_Mission::Mission_Command& cmd);
546
void do_set_home(const AP_Mission::Mission_Command& cmd);
547
void do_roi(const AP_Mission::Mission_Command& cmd);
548
void do_mount_control(const AP_Mission::Mission_Command& cmd);
549
550
bool verify_nav_wp(const AP_Mission::Mission_Command& cmd);
551
bool verify_surface(const AP_Mission::Mission_Command& cmd);
552
bool verify_RTL(void);
553
bool verify_circle(const AP_Mission::Mission_Command& cmd);
554
#if NAV_GUIDED
555
bool verify_nav_guided_enable(const AP_Mission::Mission_Command& cmd);
556
#endif
557
bool verify_nav_delay(const AP_Mission::Mission_Command& cmd);
558
559
void failsafe_leak_check();
560
void failsafe_internal_pressure_check();
561
void failsafe_internal_temperature_check();
562
563
void failsafe_terrain_act(void);
564
565
566
void translate_wpnav_rp(float &lateral_out, float &forward_out);
567
void translate_circle_nav_rp(float &lateral_out, float &forward_out);
568
void translate_pos_control_rp(float &lateral_out, float &forward_out);
569
570
void stats_update();
571
572
uint16_t get_pilot_speed_dn() const;
573
574
void convert_old_parameters(void);
575
576
#if LEAKDETECTOR_MAX_INSTANCES > 0
577
void update_leak_pins();
578
#endif
579
#if AP_RELAY_ENABLED
580
void update_relay_pins();
581
#endif
582
bool handle_do_motor_test(mavlink_command_int_t command);
583
bool init_motor_test();
584
bool verify_motor_test();
585
586
uint32_t last_do_motor_test_fail_ms = 0;
587
uint32_t last_do_motor_test_ms = 0;
588
589
bool control_check_barometer();
590
591
// vehicle specific waypoint info helpers
592
bool get_wp_distance_m(float &distance) const override;
593
bool get_wp_bearing_deg(float &bearing) const override;
594
bool get_wp_crosstrack_error_m(float &xtrack_error) const override;
595
596
enum Failsafe_Action {
597
Failsafe_Action_None = 0,
598
Failsafe_Action_Warn = 1,
599
Failsafe_Action_Disarm = 2,
600
Failsafe_Action_Surface = 3
601
};
602
603
static constexpr int8_t _failsafe_priorities[] = {
604
Failsafe_Action_Disarm,
605
Failsafe_Action_Surface,
606
Failsafe_Action_Warn,
607
Failsafe_Action_None,
608
-1 // the priority list must end with a sentinel of -1
609
};
610
611
static_assert(_failsafe_priorities[ARRAY_SIZE(_failsafe_priorities) - 1] == -1,
612
"_failsafe_priorities is missing the sentinel");
613
614
Mode *mode_from_mode_num(const Mode::Number num);
615
void exit_mode(Mode *&old_flightmode, Mode *&new_flightmode);
616
617
Mode *flightmode;
618
ModeManual mode_manual;
619
ModeStabilize mode_stabilize;
620
ModeAcro mode_acro;
621
ModeAlthold mode_althold;
622
ModeAuto mode_auto;
623
ModeGuided mode_guided;
624
ModePoshold mode_poshold;
625
ModeCircle mode_circle;
626
ModeSurface mode_surface;
627
ModeMotordetect mode_motordetect;
628
ModeSurftrak mode_surftrak;
629
630
// Auto
631
AutoSubMode auto_mode; // controls which auto controller is run
632
GuidedSubMode guided_mode;
633
634
#if AP_SCRIPTING_ENABLED
635
ScriptButton script_buttons[4];
636
#endif // AP_SCRIPTING_ENABLED
637
638
public:
639
void mainloop_failsafe_check();
640
bool rangefinder_alt_ok() const WARN_IF_UNUSED;
641
642
static Sub *_singleton;
643
644
static Sub *get_singleton() {
645
return _singleton;
646
}
647
648
#if AP_SCRIPTING_ENABLED
649
// For Lua scripting, so index is 1..4, not 0..3
650
bool is_button_pressed(uint8_t index);
651
652
// For Lua scripting, so index is 1..4, not 0..3
653
uint8_t get_and_clear_button_count(uint8_t index);
654
655
#if AP_RANGEFINDER_ENABLED
656
float get_rangefinder_target_cm() const WARN_IF_UNUSED { return mode_surftrak.get_rangefinder_target_cm(); }
657
bool set_rangefinder_target_cm(float new_target_cm) { return mode_surftrak.set_rangefinder_target_cm(new_target_cm); }
658
#endif // AP_RANGEFINDER_ENABLED
659
#endif // AP_SCRIPTING_ENABLED
660
};
661
662
extern const AP_HAL::HAL& hal;
663
extern Sub sub;
664
665