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