Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduCopter/Copter.h
9317 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 Copter 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> // Common definitions and utility routines for the ArduPilot libraries
32
#include <AP_Common/Location.h> // Library having the implementation of location class
33
#include <AP_Param/AP_Param.h> // A system for managing and storing variables that are of general interest to the system.
34
#include <StorageManager/StorageManager.h> // library for Management for hal.storage to allow for backwards compatible mapping of storage offsets to available storage
35
36
// Application dependencies
37
#include <AP_Logger/AP_Logger.h> // ArduPilot Mega Flash Memory Library
38
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
39
#include <AP_AccelCal/AP_AccelCal.h> // interface and maths for accelerometer calibration
40
#include <AP_InertialSensor/AP_InertialSensor.h> // ArduPilot Mega Inertial Sensor (accel & gyro) Library
41
#include <AP_AHRS/AP_AHRS.h> // AHRS (Attitude Heading Reference System) interface library for ArduPilot
42
#include <AP_Mission/AP_Mission.h> // Mission command library
43
#include <AP_Mission/AP_Mission_ChangeDetector.h> // Mission command change detection library
44
#include <AC_AttitudeControl/AC_AttitudeControl_Multi.h> // Attitude control library
45
#include <AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.h> // 6DoF Attitude control library
46
#include <AC_AttitudeControl/AC_AttitudeControl_Heli.h> // Attitude control library for traditional helicopter
47
#include <AC_AttitudeControl/AC_PosControl.h> // Position control library
48
#include <AC_AttitudeControl/AC_CommandModel.h> // Command model library
49
#include <AP_Motors/AP_Motors.h> // AP Motors library
50
#include <Filter/Filter.h> // Filter library
51
#include <AP_Vehicle/AP_Vehicle.h> // needed for AHRS build
52
#include <AC_WPNav/AC_WPNav.h> // ArduCopter waypoint navigation library
53
#include <AC_WPNav/AC_Loiter.h> // ArduCopter Loiter Mode Library
54
#include <AC_WPNav/AC_Circle.h> // circle navigation library
55
#include <AP_Declination/AP_Declination.h> // ArduPilot Mega Declination Helper Library
56
#include <AP_RCMapper/AP_RCMapper.h> // RC input mapping library
57
#include <AP_BattMonitor/AP_BattMonitor.h> // Battery monitor library
58
#include <AP_LandingGear/AP_LandingGear.h> // Landing Gear library
59
#include <AC_InputManager/AC_InputManager.h> // Pilot input handling library
60
#include <AC_InputManager/AC_InputManager_Heli.h> // Heli specific pilot input handling library
61
#include <AP_Arming/AP_Arming.h> // ArduPilot motor arming library
62
#include <AP_SmartRTL/AP_SmartRTL.h> // ArduPilot Smart Return To Launch Mode (SRTL) library
63
#include <AP_TempCalibration/AP_TempCalibration.h> // temperature calibration library
64
#include <AC_AutoTune/AC_AutoTune_Multi.h> // ArduCopter autotune library. support for autotune of multirotors.
65
#include <AC_AutoTune/AC_AutoTune_Heli.h> // ArduCopter autotune library. support for autotune of helicopters.
66
#include <AP_Parachute/AP_Parachute.h> // ArduPilot parachute release library
67
#include <AC_Sprayer/AC_Sprayer.h> // Crop sprayer library
68
#include <AP_Avoidance/AP_Avoidance.h> // "ADSB" avoidance library
69
#include <AP_ADSB/AP_ADSB.h> // ADS-B RF based collision avoidance module library
70
#include <AP_Proximity/AP_Proximity.h> // ArduPilot proximity sensor library
71
#include <AC_PrecLand/AC_PrecLand_config.h>
72
#include <AP_OpticalFlow/AP_OpticalFlow.h>
73
#include <AP_Winch/AP_Winch_config.h>
74
#include <AP_SurfaceDistance/AP_SurfaceDistance.h>
75
76
// Configuration
77
#include "defines.h"
78
#include "config.h"
79
80
#if FRAME_CONFIG == HELI_FRAME
81
#define MOTOR_CLASS AP_MotorsHeli
82
#else
83
#define MOTOR_CLASS AP_MotorsMulticopter
84
#endif
85
86
#if MODE_AUTOROTATE_ENABLED
87
#include <AC_Autorotation/AC_Autorotation.h> // Autorotation controllers
88
#endif
89
90
#include "RC_Channel_Copter.h" // RC Channel Library
91
92
#include "GCS_MAVLink_Copter.h"
93
#include "GCS_Copter.h"
94
#include "AP_Rally.h" // Rally point library
95
#include "AP_Arming_Copter.h"
96
97
#include <AP_ExternalControl/AP_ExternalControl_config.h>
98
#if AP_EXTERNAL_CONTROL_ENABLED
99
#include "AP_ExternalControl_Copter.h"
100
#endif
101
102
#include <AP_Beacon/AP_Beacon_config.h>
103
#if AP_BEACON_ENABLED
104
#include <AP_Beacon/AP_Beacon.h>
105
#endif
106
107
#if AP_AVOIDANCE_ENABLED
108
#include <AC_Avoidance/AC_Avoid.h>
109
#endif
110
#if AP_OAPATHPLANNER_ENABLED
111
#include <AC_WPNav/AC_WPNav_OA.h>
112
#include <AC_Avoidance/AP_OAPathPlanner.h>
113
#endif
114
#if AC_PRECLAND_ENABLED
115
# include <AC_PrecLand/AC_PrecLand.h>
116
# include <AC_PrecLand/AC_PrecLand_StateMachine.h>
117
#endif
118
#if MODE_FOLLOW_ENABLED
119
# include <AP_Follow/AP_Follow.h>
120
#endif
121
#if AP_TERRAIN_AVAILABLE
122
# include <AP_Terrain/AP_Terrain.h>
123
#endif
124
#if AP_RANGEFINDER_ENABLED
125
# include <AP_RangeFinder/AP_RangeFinder.h>
126
#endif
127
128
#include <AP_Mount/AP_Mount.h>
129
130
#include <AP_Camera/AP_Camera.h>
131
132
#if HAL_BUTTON_ENABLED
133
# include <AP_Button/AP_Button.h>
134
#endif
135
136
#if OSD_ENABLED || OSD_PARAM_ENABLED
137
#include <AP_OSD/AP_OSD.h>
138
#endif
139
140
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
141
# include "afs_copter.h"
142
#endif
143
#if TOY_MODE_ENABLED
144
# include "toy_mode.h"
145
#endif
146
#if AP_WINCH_ENABLED
147
# include <AP_Winch/AP_Winch.h>
148
#endif
149
#include <AP_RPM/AP_RPM.h>
150
151
#if AP_SCRIPTING_ENABLED
152
#include <AP_Scripting/AP_Scripting.h>
153
#endif
154
155
#if AC_CUSTOMCONTROL_MULTI_ENABLED
156
#include <AC_CustomControl/AC_CustomControl.h> // Custom control library
157
#endif
158
159
#if AP_AVOIDANCE_ENABLED && !AP_FENCE_ENABLED
160
#error AC_Avoidance relies on AP_FENCE_ENABLED which is disabled
161
#endif
162
163
#if AP_OAPATHPLANNER_ENABLED && !AP_FENCE_ENABLED
164
#error AP_OAPathPlanner relies on AP_FENCE_ENABLED which is disabled
165
#endif
166
167
#if MODE_AUTOROTATE_ENABLED && !AP_RPM_ENABLED
168
#error AC_Autorotation relies on AP_RPM_ENABLED which is disabled
169
#endif
170
171
#if HAL_ADSB_ENABLED
172
#include "avoidance_adsb.h"
173
#endif
174
// Local modules
175
#include "Parameters.h"
176
#if USER_PARAMS_ENABLED
177
#include "UserParameters.h"
178
#endif
179
#include "mode.h"
180
181
class Copter : public AP_Vehicle {
182
public:
183
friend class GCS_MAVLINK_Copter;
184
friend class GCS_Copter;
185
friend class AP_Rally_Copter;
186
friend class Parameters;
187
friend class ParametersG2;
188
friend class AP_Avoidance_Copter;
189
190
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
191
friend class AP_AdvancedFailsafe_Copter;
192
#endif
193
friend class AP_Arming_Copter;
194
#if AP_EXTERNAL_CONTROL_ENABLED
195
friend class AP_ExternalControl_Copter;
196
#endif
197
friend class ToyMode;
198
friend class RC_Channel_Copter;
199
friend class RC_Channels_Copter;
200
201
friend class AutoTune;
202
203
friend class Mode;
204
friend class ModeAcro;
205
friend class ModeAcro_Heli;
206
friend class ModeAltHold;
207
friend class ModeAuto;
208
friend class ModeAutoTune;
209
friend class ModeAvoidADSB;
210
friend class ModeBrake;
211
friend class ModeCircle;
212
friend class ModeDrift;
213
friend class ModeFlip;
214
friend class ModeFlowHold;
215
friend class ModeFollow;
216
friend class ModeGuided;
217
friend class ModeLand;
218
friend class ModeLoiter;
219
friend class ModePosHold;
220
friend class ModeRTL;
221
friend class ModeSmartRTL;
222
friend class ModeSport;
223
friend class ModeStabilize;
224
friend class ModeStabilize_Heli;
225
friend class ModeSystemId;
226
friend class ModeThrow;
227
friend class ModeZigZag;
228
friend class ModeAutorotate;
229
friend class ModeTurtle;
230
231
friend class _AutoTakeoff;
232
233
friend class PayloadPlace;
234
235
Copter(void);
236
237
private:
238
239
// Global parameters are all contained within the 'g' class.
240
Parameters g;
241
ParametersG2 g2;
242
243
// used to detect MAVLink acks from GCS to stop compassmot
244
uint8_t command_ack_counter;
245
246
// primary input control channels
247
RC_Channel *channel_roll;
248
RC_Channel *channel_pitch;
249
RC_Channel *channel_throttle;
250
RC_Channel *channel_yaw;
251
252
#if AP_RC_TRANSMITTER_TUNING_ENABLED
253
// channel which is being used to tune a parameter value:
254
RC_Channel *rc_tuning;
255
RC_Channel *rc_tuning2;
256
#endif // AP_RC_TRANSMITTER_TUNING_ENABLED
257
258
// flight modes convenience array
259
AP_Int8 *flight_modes;
260
const uint8_t num_flight_modes = 6;
261
262
AP_SurfaceDistance rangefinder_state {ROTATION_PITCH_270, 0U};
263
AP_SurfaceDistance rangefinder_up_state {ROTATION_PITCH_90, 1U};
264
265
// helper function to get inertially interpolated rangefinder height.
266
bool get_rangefinder_height_interpolated_m(float& ret) const;
267
268
#if AP_RANGEFINDER_ENABLED
269
class SurfaceTracking {
270
public:
271
272
// update_surface_offset - manages the vertical offset of the position controller to follow the
273
// measured ground or ceiling level measured using the range finder.
274
void update_surface_offset();
275
276
// target has already been set by terrain following so do not initialise again
277
// this should be called by flight modes when switching from terrain following to surface tracking (e.g. ZigZag)
278
void external_init();
279
280
// get target and actual distances (in m) for logging purposes
281
bool get_target_dist_for_logging(float &target_dist_m) const;
282
float get_dist_for_logging() const;
283
void invalidate_for_logging() { valid_for_logging = false; }
284
285
// surface tracking surface
286
enum class Surface {
287
NONE = 0,
288
GROUND = 1,
289
CEILING = 2
290
};
291
// set surface to track
292
void set_surface(Surface new_surface);
293
// initialise surface tracking
294
void init(Surface surf) { surface = surf; }
295
296
private:
297
Surface surface;
298
uint32_t last_update_ms; // system time of last update to target_alt_m
299
uint32_t last_glitch_cleared_ms; // system time of last handle glitch recovery
300
bool valid_for_logging; // true if we have a desired target altitude
301
bool reset_target; // true if target should be reset because of change in surface being tracked
302
} surface_tracking;
303
#endif
304
305
// Inertial Navigation EKF - different viewpoint
306
AP_AHRS_View *ahrs_view;
307
308
// Arming/Disarming management class
309
AP_Arming_Copter arming;
310
311
// Optical flow sensor
312
#if AP_OPTICALFLOW_ENABLED
313
AP_OpticalFlow optflow;
314
#endif
315
316
// external control library
317
#if AP_EXTERNAL_CONTROL_ENABLED
318
AP_ExternalControl_Copter external_control;
319
#endif
320
321
322
// system time in milliseconds of last recorded yaw reset from ekf
323
uint32_t ekfYawReset_ms;
324
int8_t ekf_primary_core;
325
326
// vibration check
327
struct {
328
bool high_vibes; // true while high vibration are detected
329
uint32_t start_ms; // system time high vibration were last detected
330
uint32_t clear_ms; // system time high vibrations stopped
331
} vibration_check;
332
333
// EKF variances are unfiltered and are designed to recover very quickly when possible
334
// thus failsafes should be triggered on filtered values in order to avoid transient errors
335
LowPassFilterFloat pos_variance_filt;
336
LowPassFilterFloat vel_variance_filt;
337
bool variances_valid;
338
uint32_t last_ekf_check_us;
339
340
// takeoff check
341
uint32_t takeoff_check_warning_ms; // system time user was last warned of takeoff check failure
342
343
// GCS selection
344
GCS_Copter _gcs; // avoid using this; use gcs()
345
GCS_Copter &gcs() { return _gcs; }
346
347
// User variables
348
#ifdef USERHOOK_VARIABLES
349
# include USERHOOK_VARIABLES
350
#endif
351
352
// ap_value calculates a 32-bit bitmask representing various pieces of
353
// state about the Copter. It replaces a global variable which was
354
// used to track this state.
355
uint32_t ap_value() const;
356
357
// These variables are essentially global variables. These should
358
// be removed over time. It is critical that the offsets of these
359
// variables remain unchanged - the logging is dependent on this
360
// ordering!
361
struct PACKED {
362
bool unused1; // 0
363
bool unused_was_simple_mode_byte1; // 1
364
bool unused_was_simple_mode_byte2; // 2
365
bool pre_arm_rc_check; // 3 true if rc input pre-arm checks have been completed successfully
366
bool pre_arm_check; // 4 true if all pre-arm checks (rc, accel calibration, gps lock) have been performed
367
bool auto_armed; // 5 stops auto missions from beginning until throttle is raised
368
bool unused_log_started; // 6
369
bool land_complete; // 7 true if we have detected a landing
370
bool new_radio_frame; // 8 Set true if we have new PWM data to act on from the Radio
371
bool unused_usb_connected; // 9
372
bool unused_receiver_present; // 10
373
bool compass_mot; // 11 true if we are currently performing compassmot calibration
374
bool motor_test; // 12 true if we are currently performing the motors test
375
bool initialised; // 13 true once the init_ardupilot function has completed. Extended status to GCS is not sent until this completes
376
bool land_complete_maybe; // 14 true if we may have landed (less strict version of land_complete)
377
bool throttle_zero; // 15 true if the throttle stick is at zero, debounced, determines if pilot intends shut-down when not using motor interlock
378
bool system_time_set_unused; // 16 true if the system time has been set from the GPS
379
bool gps_glitching; // 17 true if GPS glitching is affecting navigation accuracy
380
bool using_interlock; // 18 aux switch motor interlock function is in use
381
bool land_repo_active; // 19 true if the pilot is overriding the landing position
382
bool motor_interlock_switch; // 20 true if pilot is requesting motor interlock enable
383
bool in_arming_delay; // 21 true while we are armed but waiting to spin motors
384
bool initialised_params; // 22 true when the all parameters have been initialised. we cannot send parameters to the GCS until this is done
385
bool unused_compass_init_location; // 23
386
bool unused2_aux_switch_rc_override_allowed; // 24
387
bool armed_with_airmode_switch; // 25 we armed using a arming switch
388
bool prec_land_active; // 26 true if precland is active
389
} ap;
390
391
AirMode air_mode; // air mode is 0 = not-configured ; 1 = disabled; 2 = enabled;
392
bool force_flying; // force flying is enabled when true;
393
394
// This is the state of the flight control system
395
// There are multiple states defined such as STABILIZE, ACRO,
396
Mode *flightmode;
397
398
RCMapper rcmap;
399
400
// inertial nav alt when we armed
401
float arming_altitude_m;
402
403
// Failsafe
404
struct {
405
uint32_t terrain_first_failure_ms; // the first time terrain data access failed - used to calculate the duration of the failure
406
uint32_t terrain_last_failure_ms; // the most recent time terrain data access failed
407
408
int8_t radio_counter; // number of iterations with throttle below throttle_fs_value
409
410
uint8_t radio : 1; // A status flag for the radio failsafe
411
uint8_t gcs : 1; // A status flag for the ground station failsafe
412
uint8_t ekf : 1; // true if ekf failsafe has occurred
413
uint8_t terrain : 1; // true if the missing terrain data failsafe has occurred
414
uint8_t adsb : 1; // true if an adsb related failsafe has occurred
415
uint8_t deadreckon : 1; // true if a dead reckoning failsafe has triggered
416
} failsafe;
417
418
bool any_failsafe_triggered() const {
419
return failsafe.radio || battery.has_failsafed() || failsafe.gcs || failsafe.ekf || failsafe.terrain || failsafe.adsb || failsafe.deadreckon;
420
}
421
422
// dead reckoning state
423
struct {
424
bool active; // true if dead reckoning (position estimate using estimated airspeed, no position or velocity source)
425
bool timeout; // true if dead reckoning has timedout and EKF's position and velocity estimate should no longer be trusted
426
uint32_t start_ms; // system time that EKF began deadreckoning
427
} dead_reckoning;
428
429
// Motor Output
430
MOTOR_CLASS *motors;
431
const struct AP_Param::GroupInfo *motors_var_info;
432
433
float _home_bearing_rad;
434
float _home_distance_m;
435
436
// SIMPLE Mode
437
// Used to track the orientation of the vehicle for Simple mode. This value is reset at each arming
438
// or in SuperSimple mode when the vehicle leaves a 20m radius from home.
439
enum class SimpleMode {
440
NONE = 0,
441
SIMPLE = 1,
442
SUPERSIMPLE = 2,
443
} simple_mode;
444
445
float simple_cos_yaw;
446
float simple_sin_yaw;
447
float super_simple_last_bearing_rad;
448
float super_simple_cos_yaw;
449
float super_simple_sin_yaw;
450
451
// Stores initial bearing when armed - initial simple bearing is modified in super simple mode so not suitable
452
float initial_armed_bearing_rad;
453
454
// Battery Sensors
455
AP_BattMonitor battery{MASK_LOG_CURRENT,
456
FUNCTOR_BIND_MEMBER(&Copter::handle_battery_failsafe, void, const char*, const int8_t),
457
_failsafe_priorities};
458
459
#if OSD_ENABLED || OSD_PARAM_ENABLED
460
AP_OSD osd;
461
#endif
462
463
// Altitude
464
float baro_alt_m; // barometer altitude in meters above home
465
LowPassFilterVector3f land_accel_ef_filter; // accelerations for land and crash detector tests
466
467
// filtered pilot's throttle input used to cancel landing if throttle held high
468
LowPassFilterFloat rc_throttle_control_in_filter;
469
470
// 3D Location vectors
471
// Current location of the vehicle (altitude is relative to home)
472
Location current_loc;
473
474
// Attitude, Position and Waypoint navigation objects
475
// To-Do: move inertial nav up or other navigation variables down here
476
AC_AttitudeControl *attitude_control;
477
const struct AP_Param::GroupInfo *attitude_control_var_info;
478
AC_PosControl *pos_control;
479
AC_WPNav *wp_nav;
480
AC_Loiter *loiter_nav;
481
482
#if AC_CUSTOMCONTROL_MULTI_ENABLED
483
AC_CustomControl custom_control{ahrs_view, attitude_control, motors};
484
#endif
485
486
#if MODE_CIRCLE_ENABLED
487
AC_Circle *circle_nav;
488
#endif
489
490
// System Timers
491
// --------------
492
// arm_time_ms - Records when vehicle was armed. Will be Zero if we are disarmed.
493
uint32_t arm_time_ms;
494
495
// Camera
496
#if AP_CAMERA_ENABLED
497
AP_Camera camera{MASK_LOG_CAMERA};
498
#endif
499
500
// Camera/Antenna mount tracking and stabilisation stuff
501
#if HAL_MOUNT_ENABLED
502
AP_Mount camera_mount;
503
#endif
504
505
#if AP_AVOIDANCE_ENABLED
506
AC_Avoid avoid;
507
#endif
508
509
// Rally library
510
#if HAL_RALLY_ENABLED
511
AP_Rally_Copter rally;
512
#endif
513
514
// Crop Sprayer
515
#if HAL_SPRAYER_ENABLED
516
AC_Sprayer sprayer;
517
#endif
518
519
// Parachute release
520
#if HAL_PARACHUTE_ENABLED
521
AP_Parachute parachute;
522
#endif
523
524
// Landing Gear Controller
525
#if AP_LANDINGGEAR_ENABLED
526
AP_LandingGear landinggear;
527
#endif
528
529
// terrain handling
530
#if AP_TERRAIN_AVAILABLE
531
AP_Terrain terrain;
532
#endif
533
534
// Precision Landing
535
#if AC_PRECLAND_ENABLED
536
AC_PrecLand precland;
537
AC_PrecLand_StateMachine precland_statemachine;
538
#endif
539
540
// Pilot Input Management Library
541
// Only used for Helicopter for now
542
#if FRAME_CONFIG == HELI_FRAME
543
AC_InputManager_Heli input_manager;
544
#endif
545
546
#if HAL_ADSB_ENABLED
547
AP_ADSB adsb;
548
#endif // HAL_ADSB_ENABLED
549
550
#if AP_ADSB_AVOIDANCE_ENABLED
551
// avoidance of adsb enabled vehicles (normally manned vehicles)
552
AP_Avoidance_Copter avoidance_adsb{adsb};
553
#endif
554
555
// last valid RC input time
556
uint32_t last_radio_update_ms;
557
558
// last esc calibration notification update
559
uint32_t esc_calibration_notify_update_ms;
560
561
// Top-level logic
562
// setup the var_info table
563
AP_Param param_loader;
564
565
#if FRAME_CONFIG == HELI_FRAME
566
// Tradheli flags
567
typedef struct {
568
bool dynamic_flight ; // 0 // true if we are moving at a significant speed (used to turn on/off leaky I terms)
569
bool coll_stk_low ; // 1 // true when collective stick is on lower limit
570
} heli_flags_t;
571
heli_flags_t heli_flags;
572
573
int16_t hover_roll_trim_scalar_slew;
574
#endif
575
576
// ground effect detector
577
struct {
578
bool takeoff_expected;
579
bool touchdown_expected;
580
uint32_t takeoff_time_ms;
581
float takeoff_alt_m;
582
} gndeffect_state;
583
584
bool standby_active;
585
586
static const AP_Scheduler::Task scheduler_tasks[];
587
static const AP_Param::Info var_info[];
588
static const struct LogStructure log_structure[];
589
590
// enum for ESC CALIBRATION
591
enum ESCCalibrationModes : uint8_t {
592
ESCCAL_NONE = 0,
593
ESCCAL_PASSTHROUGH_IF_THROTTLE_HIGH = 1,
594
ESCCAL_PASSTHROUGH_ALWAYS = 2,
595
ESCCAL_AUTO = 3,
596
ESCCAL_DISABLED = 9,
597
};
598
599
enum class FailsafeAction : uint8_t {
600
NONE = 0,
601
LAND = 1,
602
RTL = 2,
603
SMARTRTL = 3,
604
SMARTRTL_LAND = 4,
605
TERMINATE = 5,
606
AUTO_DO_LAND_START = 6,
607
BRAKE_LAND = 7
608
};
609
610
enum class FailsafeOption {
611
RC_CONTINUE_IF_AUTO = (1<<0), // 1
612
GCS_CONTINUE_IF_AUTO = (1<<1), // 2
613
RC_CONTINUE_IF_GUIDED = (1<<2), // 4
614
CONTINUE_IF_LANDING = (1<<3), // 8
615
GCS_CONTINUE_IF_PILOT_CONTROL = (1<<4), // 16
616
RELEASE_GRIPPER = (1<<5), // 32
617
};
618
619
620
enum class FlightOption : uint32_t {
621
DISABLE_THRUST_LOSS_CHECK = (1<<0), // 1
622
DISABLE_YAW_IMBALANCE_WARNING = (1<<1), // 2
623
RELEASE_GRIPPER_ON_THRUST_LOSS = (1<<2), // 4
624
};
625
626
// type of fast rate attitude controller in operation
627
enum class FastRateType : uint8_t {
628
FAST_RATE_DISABLED = 0,
629
FAST_RATE_DYNAMIC = 1,
630
FAST_RATE_FIXED_ARMED = 2,
631
FAST_RATE_FIXED = 3,
632
};
633
634
FastRateType get_fast_rate_type() const { return FastRateType(g2.att_enable.get()); }
635
636
// returns true if option is enabled for this vehicle
637
bool option_is_enabled(FlightOption option) const {
638
return (g2.flight_options & uint32_t(option)) != 0;
639
}
640
641
static constexpr int8_t _failsafe_priorities[] = {
642
(int8_t)FailsafeAction::TERMINATE,
643
(int8_t)FailsafeAction::LAND,
644
(int8_t)FailsafeAction::RTL,
645
(int8_t)FailsafeAction::SMARTRTL_LAND,
646
(int8_t)FailsafeAction::SMARTRTL,
647
(int8_t)FailsafeAction::NONE,
648
-1 // the priority list must end with a sentinel of -1
649
};
650
651
#define FAILSAFE_LAND_PRIORITY 1
652
static_assert(_failsafe_priorities[FAILSAFE_LAND_PRIORITY] == (int8_t)FailsafeAction::LAND,
653
"FAILSAFE_LAND_PRIORITY must match the entry in _failsafe_priorities");
654
static_assert(_failsafe_priorities[ARRAY_SIZE(_failsafe_priorities) - 1] == -1,
655
"_failsafe_priorities is missing the sentinel");
656
657
658
659
// AP_State.cpp
660
void set_auto_armed(bool b);
661
void set_simple_mode(SimpleMode b);
662
void set_failsafe_radio(bool b);
663
void set_failsafe_gcs(bool b);
664
void update_using_interlock();
665
666
// Copter.cpp
667
void get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
668
uint8_t &task_count,
669
uint32_t &log_bit) override;
670
#if AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED
671
#if MODE_GUIDED_ENABLED
672
bool set_target_location(const Location& target_loc) override;
673
bool start_takeoff(const float alt_m) override;
674
#endif // MODE_GUIDED_ENABLED
675
#endif // AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED
676
677
#if AP_SCRIPTING_ENABLED
678
#if MODE_GUIDED_ENABLED
679
bool get_target_location(Location& target_loc) override;
680
bool update_target_location(const Location &old_loc, const Location &new_loc) override;
681
bool set_target_pos_NED(const Vector3f& target_pos, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool yaw_relative, bool is_terrain_alt) override;
682
bool set_target_posvel_NED(const Vector3f& target_pos, const Vector3f& target_vel) override;
683
bool set_target_posvelaccel_NED(const Vector3f& target_pos, const Vector3f& target_vel, const Vector3f& target_accel, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool yaw_relative) override;
684
bool set_target_velocity_NED(const Vector3f& vel_ned, bool align_yaw_to_target) override;
685
bool set_target_velaccel_NED(const Vector3f& target_vel, const Vector3f& target_accel, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool relative_yaw) override;
686
bool set_target_angle_and_climbrate(float roll_deg, float pitch_deg, float yaw_deg, float climb_rate_ms, bool use_yaw_rate, float yaw_rate_degs) override;
687
bool set_target_rate_and_throttle(float roll_rate_dps, float pitch_rate_dps, float yaw_rate_dps, float throttle) override;
688
bool set_target_angle_and_rate_and_throttle(float roll_deg, float pitch_deg, float yaw_deg, float roll_rate_degs, float pitch_rate_degs, float yaw_rate_degs, float throttle) override;
689
690
// Register a custom mode with given number and names
691
AP_Vehicle::custom_mode_state* register_custom_mode(const uint8_t number, const char* full_name, const char* short_name) override;
692
#endif
693
#if MODE_CIRCLE_ENABLED
694
bool get_circle_radius(float &radius_m) override;
695
bool set_circle_rate(float rate_dps) override;
696
#endif
697
bool set_desired_speed(float speed) override;
698
#if MODE_AUTO_ENABLED
699
bool nav_scripting_enable(uint8_t mode) override;
700
bool nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2, int16_t &arg3, int16_t &arg4) override;
701
void nav_script_time_done(uint16_t id) override;
702
#endif
703
// lua scripts use this to retrieve EKF failsafe state
704
// returns true if the EKF failsafe has triggered
705
bool has_ekf_failsafed() const override;
706
#endif // AP_SCRIPTING_ENABLED
707
bool is_landing() const override;
708
bool is_taking_off() const override;
709
void rc_loop();
710
void throttle_loop();
711
void update_batt_compass(void);
712
void loop_rate_logging();
713
void ten_hz_logging_loop();
714
void twentyfive_hz_logging();
715
void three_hz_loop();
716
void one_hz_loop();
717
void init_simple_bearing();
718
void update_simple_mode(void);
719
void update_super_simple_bearing(bool force_update);
720
void read_AHRS(void);
721
void update_altitude();
722
bool get_wp_distance_m(float &distance) const override;
723
bool get_wp_bearing_deg(float &bearing) const override;
724
bool get_wp_crosstrack_error_m(float &xtrack_error) const override;
725
bool get_rate_ef_targets(Vector3f& rate_ef_targets) const override;
726
727
// Attitude.cpp
728
void update_throttle_hover();
729
float get_pilot_desired_climb_rate_ms();
730
float get_non_takeoff_throttle();
731
void set_accel_throttle_I_from_pilot_throttle();
732
uint16_t get_pilot_speed_dn() const;
733
void run_rate_controller_main();
734
735
// if AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED
736
struct RateControllerRates {
737
uint8_t fast_logging_rate;
738
uint8_t medium_logging_rate;
739
uint8_t filter_rate;
740
uint8_t main_loop_rate;
741
};
742
743
uint8_t calc_gyro_decimation(uint8_t gyro_decimation, uint16_t rate_hz);
744
void rate_controller_thread();
745
void rate_controller_filter_update();
746
void rate_controller_log_update();
747
void rate_controller_set_rates(uint8_t rate_decimation, RateControllerRates& rates, bool warn_cpu_high);
748
void enable_fast_rate_loop(uint8_t rate_decimation, RateControllerRates& rates);
749
void disable_fast_rate_loop(RateControllerRates& rates);
750
void update_dynamic_notch_at_specified_rate_main();
751
// endif AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED
752
753
#if AC_CUSTOMCONTROL_MULTI_ENABLED
754
void run_custom_controller() { custom_control.update(); }
755
#endif
756
757
// avoidance.cpp
758
void low_alt_avoidance();
759
760
#if HAL_ADSB_ENABLED || AP_ADSB_AVOIDANCE_ENABLED
761
// avoidance_adsb.cpp
762
void avoidance_adsb_update(void);
763
#endif // HAL_ADSB_ENABLED || AP_ADSB_AVOIDANCE_ENABLED
764
765
// baro_ground_effect.cpp
766
void update_ground_effect_detector(void);
767
void update_ekf_terrain_height_stable();
768
769
// commands.cpp
770
void update_home_from_EKF();
771
void set_home_to_current_location_inflight();
772
bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED;
773
bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED;
774
775
// compassmot.cpp
776
MAV_RESULT mavlink_compassmot(const GCS_MAVLINK &gcs_chan);
777
778
// crash_check.cpp
779
void crash_check();
780
void thrust_loss_check();
781
void yaw_imbalance_check();
782
LowPassFilterFloat yaw_I_filt{0.05f};
783
uint32_t last_yaw_warn_ms;
784
void parachute_check();
785
void parachute_release();
786
void parachute_manual_release();
787
788
// ekf_check.cpp
789
void ekf_check();
790
bool ekf_over_threshold();
791
void failsafe_ekf_event();
792
void failsafe_ekf_off_event(void);
793
void failsafe_ekf_recheck();
794
void check_ekf_reset();
795
void check_vibration();
796
797
// esc_calibration.cpp
798
void esc_calibration_startup_check();
799
void esc_calibration_passthrough();
800
void esc_calibration_auto();
801
void esc_calibration_notify();
802
void esc_calibration_setup();
803
804
// events.cpp
805
bool failsafe_option(FailsafeOption opt) const;
806
void failsafe_radio_on_event();
807
void failsafe_radio_off_event();
808
void handle_battery_failsafe(const char* type_str, const int8_t action);
809
void failsafe_gcs_check();
810
void failsafe_gcs_on_event(void);
811
void failsafe_gcs_off_event(void);
812
void failsafe_terrain_check();
813
void failsafe_terrain_set_status(bool data_ok);
814
void failsafe_terrain_on_event();
815
void gpsglitch_check();
816
void failsafe_deadreckon_check();
817
void set_mode_RTL_or_land_with_pause(ModeReason reason);
818
void set_mode_SmartRTL_or_RTL(ModeReason reason);
819
void set_mode_SmartRTL_or_land_with_pause(ModeReason reason);
820
void set_mode_auto_do_land_start_or_RTL(ModeReason reason);
821
void set_mode_brake_or_land_with_pause(ModeReason reason);
822
bool should_disarm_on_failsafe();
823
void do_failsafe_action(FailsafeAction action, ModeReason reason);
824
void announce_failsafe(const char *type, const char *action_undertaken=nullptr);
825
826
// failsafe.cpp
827
void failsafe_enable();
828
void failsafe_disable();
829
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
830
void afs_fs_check(void);
831
#endif
832
833
// fence.cpp
834
#if AP_FENCE_ENABLED
835
void fence_check();
836
void fence_checks_async() override;
837
#endif
838
839
// heli.cpp
840
void heli_init();
841
void check_dynamic_flight(void);
842
bool should_use_landing_swash() const;
843
void update_heli_control_dynamics(void);
844
void heli_update_landing_swash();
845
float get_pilot_desired_rotor_speed() const;
846
void heli_update_rotor_speed_targets();
847
void heli_update_autorotation();
848
void update_collective_low_flag(int16_t throttle_control);
849
850
// inertia.cpp
851
void read_inertia();
852
853
// landing_detector.cpp
854
void update_land_and_crash_detectors();
855
void update_land_detector();
856
void set_land_complete(bool b);
857
void set_land_complete_maybe(bool b);
858
void update_throttle_mix();
859
bool get_force_flying() const;
860
#if HAL_LOGGING_ENABLED
861
enum class LandDetectorLoggingFlag : uint16_t {
862
LANDED = 1U << 0,
863
LANDED_MAYBE = 1U << 1,
864
LANDING = 1U << 2,
865
STANDBY_ACTIVE = 1U << 3,
866
WOW = 1U << 4,
867
RANGEFINDER_BELOW_2M = 1U << 5,
868
DESCENT_RATE_LOW = 1U << 6,
869
ACCEL_STATIONARY = 1U << 7,
870
LARGE_ANGLE_ERROR = 1U << 8,
871
LARGE_ANGLE_REQUEST = 1U << 8,
872
MOTOR_AT_LOWER_LIMIT = 1U << 9,
873
THROTTLE_MIX_AT_MIN = 1U << 10,
874
};
875
struct {
876
uint32_t last_logged_ms;
877
uint32_t last_logged_count;
878
uint16_t last_logged_flags;
879
} land_detector;
880
void Log_LDET(uint16_t logging_flags, uint32_t land_detector_count);
881
#endif
882
883
#if AP_LANDINGGEAR_ENABLED
884
// landing_gear.cpp
885
void landinggear_update();
886
#endif
887
888
// standby.cpp
889
void standby_update();
890
891
#if HAL_LOGGING_ENABLED
892
// methods for AP_Vehicle:
893
const AP_Int32 &get_log_bitmask() override { return g.log_bitmask; }
894
const struct LogStructure *get_log_structures() const override {
895
return log_structure;
896
}
897
uint8_t get_num_log_structures() const override;
898
899
// Log.cpp
900
void Log_Write_Control_Tuning();
901
void Log_Write_Attitude();
902
void Log_Write_Rate();
903
void Log_Write_EKF_POS();
904
void Log_Write_PIDS();
905
void Log_Write_Data(LogDataID id, int32_t value);
906
void Log_Write_Data(LogDataID id, uint32_t value);
907
void Log_Write_Data(LogDataID id, int16_t value);
908
void Log_Write_Data(LogDataID id, uint16_t value);
909
void Log_Write_Data(LogDataID id, float value);
910
void Log_Write_PTUN(uint8_t param, float tuning_val, float tune_min, float tune_max, float norm_in);
911
void Log_Video_Stabilisation();
912
void Log_Write_Guided_Position_Target(ModeGuided::SubMode submode, const Vector3p& pos_target_ned_m, bool is_terrain_alt, const Vector3f& vel_target_ms, const Vector3f& accel_target_mss);
913
void Log_Write_Guided_Attitude_Target(ModeGuided::SubMode submode, float roll, float pitch, float yaw, const Vector3f &ang_vel, float thrust, float climb_rate);
914
void Log_Write_SysID_Setup(uint8_t systemID_axis, float waveform_magnitude, float frequency_start, float frequency_stop, float time_fade_in, float time_const_freq, float time_record, float time_fade_out);
915
void Log_Write_SysID_Data(float waveform_time, float waveform_sample, float waveform_freq, float angle_x, float angle_y, float angle_z, float accel_x, float accel_y, float accel_z);
916
void Log_Write_Vehicle_Startup_Messages();
917
void Log_Write_Rate_Thread_Dt(float dt, float dtAvg, float dtMax, float dtMin);
918
#endif // HAL_LOGGING_ENABLED
919
920
// mode.cpp
921
bool set_mode(Mode::Number mode, ModeReason reason);
922
bool set_mode(const uint8_t new_mode, const ModeReason reason) override;
923
ModeReason _last_reason;
924
// called when an attempt to change into a mode is unsuccessful:
925
void mode_change_failed(const Mode *mode, const char *reason);
926
uint8_t get_mode() const override { return (uint8_t)flightmode->mode_number(); }
927
bool current_mode_requires_mission() const override;
928
void update_flight_mode();
929
void notify_flight_mode();
930
931
// Check if this mode can be entered from the GCS
932
bool gcs_mode_enabled(const Mode::Number mode_num);
933
934
// mode_land.cpp
935
void set_mode_land_with_pause(ModeReason reason);
936
bool landing_with_GPS();
937
938
// motor_test.cpp
939
void motor_test_output();
940
bool mavlink_motor_control_check(const GCS_MAVLINK &gcs_chan, bool check_rc, const char* mode);
941
MAV_RESULT mavlink_motor_test_start(const GCS_MAVLINK &gcs_chan, uint8_t motor_seq, uint8_t throttle_type, float throttle_value, float timeout_sec, uint8_t motor_count);
942
void motor_test_stop();
943
944
// motors.cpp
945
void auto_disarm_check();
946
void motors_output(bool full_push = true);
947
void motors_output_main();
948
void lost_vehicle_check();
949
950
// navigation.cpp
951
void run_nav_updates(void);
952
float home_bearing_rad();
953
float home_distance_m();
954
955
// Parameters.cpp
956
void load_parameters(void) override;
957
void convert_pid_parameters(void);
958
#if HAL_PROXIMITY_ENABLED
959
void convert_prx_parameters();
960
#endif
961
962
// precision_landing.cpp
963
void init_precland();
964
void update_precland();
965
966
// radio.cpp
967
void default_dead_zones();
968
void init_rc_in();
969
void init_rc_out();
970
void read_radio();
971
void set_throttle_and_failsafe(uint16_t throttle_pwm);
972
void set_throttle_zero_flag(int16_t throttle_control);
973
void radio_passthrough_to_motors();
974
int16_t get_throttle_mid(void);
975
976
// sensors.cpp
977
void read_barometer(void);
978
void init_rangefinder(void);
979
void read_rangefinder(void);
980
bool rangefinder_alt_ok() const;
981
bool rangefinder_up_ok() const;
982
void update_rangefinder_terrain_offset();
983
984
// takeoff_check.cpp
985
void takeoff_check();
986
987
// system.cpp
988
void init_ardupilot() override;
989
void startup_INS_ground();
990
bool position_ok() const;
991
bool ekf_has_absolute_position() const;
992
bool ekf_has_relative_position() const;
993
bool ekf_alt_ok() const;
994
void update_auto_armed();
995
bool should_log(uint32_t mask);
996
const char* get_frame_string() const;
997
void allocate_motors(void);
998
bool is_tradheli() const;
999
1000
// terrain.cpp
1001
void terrain_update();
1002
void terrain_logging();
1003
1004
#if AP_RC_TRANSMITTER_TUNING_ENABLED
1005
// tuning.cpp
1006
void tuning();
1007
void tuning(const class RC_Channel *tuning_ch, int8_t tuning_param, float tuning_min, float tuning_max);
1008
bool being_tuned(int8_t tuning_param) const;
1009
#endif // AP_RC_TRANSMITTER_TUNING_ENABLED
1010
1011
// UserCode.cpp
1012
void userhook_init();
1013
void userhook_FastLoop();
1014
void userhook_50Hz();
1015
void userhook_MediumLoop();
1016
void userhook_SlowLoop();
1017
void userhook_SuperSlowLoop();
1018
void userhook_auxSwitch1(const RC_Channel::AuxSwitchPos ch_flag);
1019
void userhook_auxSwitch2(const RC_Channel::AuxSwitchPos ch_flag);
1020
void userhook_auxSwitch3(const RC_Channel::AuxSwitchPos ch_flag);
1021
1022
#if MODE_ACRO_ENABLED
1023
#if FRAME_CONFIG == HELI_FRAME
1024
ModeAcro_Heli mode_acro;
1025
#else
1026
ModeAcro mode_acro;
1027
#endif
1028
#endif
1029
ModeAltHold mode_althold;
1030
#if MODE_AUTO_ENABLED
1031
ModeAuto mode_auto;
1032
#endif
1033
#if AUTOTUNE_ENABLED
1034
ModeAutoTune mode_autotune;
1035
#endif
1036
#if MODE_BRAKE_ENABLED
1037
ModeBrake mode_brake;
1038
#endif
1039
#if MODE_CIRCLE_ENABLED
1040
ModeCircle mode_circle;
1041
#endif
1042
#if MODE_DRIFT_ENABLED
1043
ModeDrift mode_drift;
1044
#endif
1045
#if MODE_FLIP_ENABLED
1046
ModeFlip mode_flip;
1047
#endif
1048
#if MODE_FOLLOW_ENABLED
1049
ModeFollow mode_follow;
1050
#endif
1051
#if MODE_GUIDED_ENABLED
1052
ModeGuided mode_guided;
1053
#if AP_SCRIPTING_ENABLED
1054
// Custom modes registered at runtime
1055
ModeGuidedCustom *mode_guided_custom[5];
1056
#endif
1057
#endif
1058
ModeLand mode_land;
1059
#if MODE_LOITER_ENABLED
1060
ModeLoiter mode_loiter;
1061
#endif
1062
#if MODE_POSHOLD_ENABLED
1063
ModePosHold mode_poshold;
1064
#endif
1065
#if MODE_RTL_ENABLED
1066
ModeRTL mode_rtl;
1067
#endif
1068
#if FRAME_CONFIG == HELI_FRAME
1069
ModeStabilize_Heli mode_stabilize;
1070
#else
1071
ModeStabilize mode_stabilize;
1072
#endif
1073
#if MODE_SPORT_ENABLED
1074
ModeSport mode_sport;
1075
#endif
1076
#if MODE_SYSTEMID_ENABLED
1077
ModeSystemId mode_systemid;
1078
#endif
1079
#if AP_ADSB_AVOIDANCE_ENABLED
1080
ModeAvoidADSB mode_avoid_adsb;
1081
#endif // AP_ADSB_AVOIDANCE_ENABLED
1082
#if MODE_THROW_ENABLED
1083
ModeThrow mode_throw;
1084
#endif
1085
#if MODE_GUIDED_NOGPS_ENABLED
1086
ModeGuidedNoGPS mode_guided_nogps;
1087
#endif
1088
#if MODE_SMARTRTL_ENABLED
1089
ModeSmartRTL mode_smartrtl;
1090
#endif
1091
#if MODE_FLOWHOLD_ENABLED
1092
ModeFlowHold mode_flowhold;
1093
#endif
1094
#if MODE_ZIGZAG_ENABLED
1095
ModeZigZag mode_zigzag;
1096
#endif
1097
#if MODE_AUTOROTATE_ENABLED
1098
ModeAutorotate mode_autorotate;
1099
#endif
1100
#if MODE_TURTLE_ENABLED
1101
ModeTurtle mode_turtle;
1102
#endif
1103
1104
// mode.cpp
1105
Mode *mode_from_mode_num(const Mode::Number mode);
1106
void exit_mode(Mode *&old_flightmode, Mode *&new_flightmode);
1107
1108
bool started_rate_thread;
1109
bool using_rate_thread;
1110
1111
public:
1112
void failsafe_check(); // failsafe.cpp
1113
};
1114
1115
extern Copter copter;
1116
1117
using AP_HAL::millis;
1118
using AP_HAL::micros;
1119
1120