ArduCopter
Copter.h
Go to the documentation of this file.
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 
21 // Header includes
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 
36 // Application dependencies
37 #include <GCS_MAVLink/GCS.h>
38 #include <AP_SerialManager/AP_SerialManager.h> // Serial manager library
39 #include <AP_GPS/AP_GPS.h> // ArduPilot GPS library
40 #include <DataFlash/DataFlash.h> // ArduPilot Mega Flash Memory Library
41 #include <AP_ADC/AP_ADC.h> // ArduPilot Mega Analog to Digital Converter Library
42 #include <AP_Baro/AP_Baro.h>
43 #include <AP_Compass/AP_Compass.h> // ArduPilot Mega Magnetometer Library
44 #include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
45 #include <AP_AccelCal/AP_AccelCal.h> // interface and maths for accelerometer calibration
46 #include <AP_InertialSensor/AP_InertialSensor.h> // ArduPilot Mega Inertial Sensor (accel & gyro) Library
47 #include <AP_AHRS/AP_AHRS.h>
48 #include <AP_NavEKF2/AP_NavEKF2.h>
49 #include <AP_NavEKF3/AP_NavEKF3.h>
50 #include <AP_Mission/AP_Mission.h> // Mission command library
51 #include <AC_PID/AC_P.h> // P library
52 #include <AC_PID/AC_PID.h> // PID library
53 #include <AC_PID/AC_PI_2D.h> // PI library (2-axis)
54 #include <AC_PID/AC_PID_2D.h> // PID library (2-axis)
55 #include <AC_PID/AC_HELI_PID.h> // Heli specific Rate PID library
56 #include <AC_AttitudeControl/AC_AttitudeControl_Multi.h> // Attitude control library
57 #include <AC_AttitudeControl/AC_AttitudeControl_Heli.h> // Attitude control library for traditional helicopter
58 #include <AC_AttitudeControl/AC_PosControl.h> // Position control library
59 #include <RC_Channel/RC_Channel.h> // RC Channel Library
60 #include <AP_Motors/AP_Motors.h> // AP Motors library
61 #include <AP_Stats/AP_Stats.h> // statistics library
62 #include <AP_RSSI/AP_RSSI.h> // RSSI Library
63 #include <Filter/Filter.h> // Filter library
64 #include <AP_Buffer/AP_Buffer.h> // APM FIFO Buffer
65 #include <AP_Relay/AP_Relay.h> // APM relay
66 #include <AP_ServoRelayEvents/AP_ServoRelayEvents.h>
67 #include <AP_Airspeed/AP_Airspeed.h> // needed for AHRS build
68 #include <AP_Vehicle/AP_Vehicle.h> // needed for AHRS build
69 #include <AP_InertialNav/AP_InertialNav.h> // ArduPilot Mega inertial navigation library
70 #include <AC_WPNav/AC_WPNav.h> // ArduCopter waypoint navigation library
71 #include <AC_WPNav/AC_Loiter.h>
72 #include <AC_WPNav/AC_Circle.h> // circle navigation library
73 #include <AP_Declination/AP_Declination.h> // ArduPilot Mega Declination Helper Library
74 #include <AP_Scheduler/AP_Scheduler.h> // main loop scheduler
75 #include <AP_RCMapper/AP_RCMapper.h> // RC input mapping library
76 #include <AP_Notify/AP_Notify.h> // Notify library
77 #include <AP_BattMonitor/AP_BattMonitor.h> // Battery monitor library
78 #include <AP_BoardConfig/AP_BoardConfig.h> // board configuration library
79 #include <AP_BoardConfig/AP_BoardConfig_CAN.h>
80 #include <AP_LandingGear/AP_LandingGear.h> // Landing Gear library
81 #include <AC_InputManager/AC_InputManager.h> // Pilot input handling library
82 #include <AC_InputManager/AC_InputManager_Heli.h> // Heli specific pilot input handling library
83 #include <AP_Button/AP_Button.h>
84 #include <AP_Arming/AP_Arming.h>
85 #include <AP_SmartRTL/AP_SmartRTL.h>
86 #include <AP_TempCalibration/AP_TempCalibration.h>
87 
88 // Configuration
89 #include "defines.h"
90 #include "config.h"
91 
92 #include "GCS_Mavlink.h"
93 #include "GCS_Copter.h"
94 #include "AP_Rally.h" // Rally point library
95 #include "AP_Arming.h"
96 
97 // libraries which are dependent on #defines in defines.h and/or config.h
98 #if BEACON_ENABLED == ENABLED
99  #include <AP_Beacon/AP_Beacon.h>
100 #endif
101 #if AC_AVOID_ENABLED == ENABLED
102  #include <AC_Avoidance/AC_Avoid.h>
103 #endif
104 #if SPRAYER == ENABLED
105  # include <AC_Sprayer/AC_Sprayer.h>
106 #endif
107 #if GRIPPER_ENABLED == ENABLED
108  # include <AP_Gripper/AP_Gripper.h>
109 #endif
110 #if PARACHUTE == ENABLED
111  # include <AP_Parachute/AP_Parachute.h>
112 #endif
113 #if PRECISION_LANDING == ENABLED
114  # include <AC_PrecLand/AC_PrecLand.h>
115  # include <AP_IRLock/AP_IRLock.h>
116 #endif
117 #if FRSKY_TELEM_ENABLED == ENABLED
118  # include <AP_Frsky_Telem/AP_Frsky_Telem.h>
119 #endif
120 #if ADSB_ENABLED == ENABLED
121  # include <AP_ADSB/AP_ADSB.h>
122 #endif
123 #if MODE_FOLLOW_ENABLED == ENABLED
124  # include <AP_Follow/AP_Follow.h>
125 #endif
126 #if AC_FENCE == ENABLED
127  # include <AC_Fence/AC_Fence.h>
128 #endif
129 #if AC_TERRAIN == ENABLED
130  # include <AP_Terrain/AP_Terrain.h>
131 #endif
132 #if OPTFLOW == ENABLED
133  # include <AP_OpticalFlow/AP_OpticalFlow.h>
134 #endif
135 #if VISUAL_ODOMETRY_ENABLED == ENABLED
136  # include <AP_VisualOdom/AP_VisualOdom.h>
137 #endif
138 #if RANGEFINDER_ENABLED == ENABLED
139  # include <AP_RangeFinder/AP_RangeFinder.h>
140 #endif
141 #if PROXIMITY_ENABLED == ENABLED
142  # include <AP_Proximity/AP_Proximity.h>
143 #endif
144 #if MOUNT == ENABLED
145  #include <AP_Mount/AP_Mount.h>
146 #endif
147 #if CAMERA == ENABLED
148  # include <AP_Camera/AP_Camera.h>
149 #endif
150 
151 #if DEVO_TELEM_ENABLED == ENABLED
152  #include <AP_Devo_Telem/AP_Devo_Telem.h>
153 #endif
154 
155 #if ADVANCED_FAILSAFE == ENABLED
156  # include "afs_copter.h"
157 #endif
158 #if TOY_MODE_ENABLED == ENABLED
159  # include "toy_mode.h"
160 #endif
161 #if WINCH_ENABLED == ENABLED
162  # include <AP_WheelEncoder/AP_WheelEncoder.h>
163  # include <AP_Winch/AP_Winch.h>
164 #endif
165 #if RPM_ENABLED == ENABLED
166  #include <AP_RPM/AP_RPM.h>
167 #endif
168 
169 // Local modules
170 #include "Parameters.h"
171 #if ADSB_ENABLED == ENABLED
172 #include "avoidance_adsb.h"
173 #endif
174 
175 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
176 #include <SITL/SITL.h>
177 #endif
178 
179 
180 class Copter : public AP_HAL::HAL::Callbacks {
181 public:
182  friend class GCS_MAVLINK_Copter;
183  friend class GCS_Copter;
184  friend class AP_Rally_Copter;
185  friend class Parameters;
186  friend class ParametersG2;
187  friend class AP_Avoidance_Copter;
188 
189 #if ADVANCED_FAILSAFE == ENABLED
190  friend class AP_AdvancedFailsafe_Copter;
191 #endif
192  friend class AP_Arming_Copter;
193  friend class ToyMode;
194 
195  Copter(void);
196 
197  // HAL::Callbacks implementation.
198  void setup() override;
199  void loop() override;
200 
201 private:
202  static const AP_FWVersion fwver;
203 
204  // key aircraft parameters passed to multiple libraries
205  AP_Vehicle::MultiCopter aparm;
206 
207  // Global parameters are all contained within the 'g' class.
208  Parameters g;
209  ParametersG2 g2;
210 
211  // main loop scheduler
212  AP_Scheduler scheduler{FUNCTOR_BIND_MEMBER(&Copter::fast_loop, void)};
213 
214  // AP_Notify instance
215  AP_Notify notify;
216 
217  // used to detect MAVLink acks from GCS to stop compassmot
218  uint8_t command_ack_counter;
219 
220  // primary input control channels
221  RC_Channel *channel_roll;
222  RC_Channel *channel_pitch;
223  RC_Channel *channel_throttle;
224  RC_Channel *channel_yaw;
225 
226  // Dataflash
227  DataFlash_Class DataFlash;
228 
229  AP_GPS gps;
230 
231  // flight modes convenience array
232  AP_Int8 *flight_modes;
233 
234  AP_Baro barometer;
235  Compass compass;
236  AP_InertialSensor ins;
237 
238  RangeFinder rangefinder{serial_manager, ROTATION_PITCH_270};
239  struct {
240  bool enabled:1;
241  bool alt_healthy:1; // true if we can trust the altitude from the rangefinder
242  int16_t alt_cm; // tilt compensated altitude (in cm) from rangefinder
243  uint32_t last_healthy_ms;
244  LowPassFilterFloat alt_cm_filt; // altitude filter
245  int8_t glitch_count;
246  } rangefinder_state = { false, false, 0, 0 };
247 
248 #if RPM_ENABLED == ENABLED
249  AP_RPM rpm_sensor;
250 #endif
251 
252  // Inertial Navigation EKF
253  NavEKF2 EKF2{&ahrs, rangefinder};
254  NavEKF3 EKF3{&ahrs, rangefinder};
255  AP_AHRS_NavEKF ahrs{EKF2, EKF3, AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF};
256 
257 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
258  SITL::SITL sitl;
259 #endif
260 
261  // Mission library
262 #if MODE_AUTO_ENABLED == ENABLED
263  AP_Mission mission{ahrs,
264  FUNCTOR_BIND_MEMBER(&Copter::start_command, bool, const AP_Mission::Mission_Command &),
265  FUNCTOR_BIND_MEMBER(&Copter::verify_command_callback, bool, const AP_Mission::Mission_Command &),
266  FUNCTOR_BIND_MEMBER(&Copter::exit_mission, void)};
267 
268  bool start_command(const AP_Mission::Mission_Command& cmd) {
269  return mode_auto.start_command(cmd);
270  }
271  bool verify_command_callback(const AP_Mission::Mission_Command& cmd) {
272  return mode_auto.verify_command_callback(cmd);
273  }
274  void exit_mission() {
275  mode_auto.exit_mission();
276  }
277 #endif
278 
279  // Arming/Disarming mangement class
280  AP_Arming_Copter arming{ahrs, compass, battery, inertial_nav};
281 
282  // Optical flow sensor
283 #if OPTFLOW == ENABLED
284  OpticalFlow optflow{ahrs};
285 #endif
286 
287  // gnd speed limit required to observe optical flow sensor limits
288  float ekfGndSpdLimit;
289 
290  // scale factor applied to velocity controller gain to prevent optical flow noise causing excessive angle demand noise
291  float ekfNavVelGainScaler;
292 
293  // system time in milliseconds of last recorded yaw reset from ekf
294  uint32_t ekfYawReset_ms;
295  int8_t ekf_primary_core;
296 
297  AP_SerialManager serial_manager;
298 
299  // GCS selection
300  GCS_Copter _gcs; // avoid using this; use gcs()
301  GCS_Copter &gcs() { return _gcs; }
302 
303  // User variables
304 #ifdef USERHOOK_VARIABLES
305 # include USERHOOK_VARIABLES
306 #endif
307 
308  // Documentation of GLobals:
309  typedef union {
310  struct {
311  uint8_t unused1 : 1; // 0
312  uint8_t simple_mode : 2; // 1,2 // This is the state of simple mode : 0 = disabled ; 1 = SIMPLE ; 2 = SUPERSIMPLE
313  uint8_t pre_arm_rc_check : 1; // 3 // true if rc input pre-arm checks have been completed successfully
314  uint8_t pre_arm_check : 1; // 4 // true if all pre-arm checks (rc, accel calibration, gps lock) have been performed
315  uint8_t auto_armed : 1; // 5 // stops auto missions from beginning until throttle is raised
316  uint8_t logging_started : 1; // 6 // true if dataflash logging has started
317  uint8_t land_complete : 1; // 7 // true if we have detected a landing
318  uint8_t new_radio_frame : 1; // 8 // Set true if we have new PWM data to act on from the Radio
319  uint8_t usb_connected : 1; // 9 // true if APM is powered from USB connection
320  uint8_t rc_receiver_present : 1; // 10 // true if we have an rc receiver present (i.e. if we've ever received an update
321  uint8_t compass_mot : 1; // 11 // true if we are currently performing compassmot calibration
322  uint8_t motor_test : 1; // 12 // true if we are currently performing the motors test
323  uint8_t initialised : 1; // 13 // true once the init_ardupilot function has completed. Extended status to GCS is not sent until this completes
324  uint8_t land_complete_maybe : 1; // 14 // true if we may have landed (less strict version of land_complete)
325  uint8_t throttle_zero : 1; // 15 // true if the throttle stick is at zero, debounced, determines if pilot intends shut-down when not using motor interlock
326  uint8_t system_time_set : 1; // 16 // true if the system time has been set from the GPS
327  uint8_t gps_glitching : 1; // 17 // true if GPS glitching is affecting navigation accuracy
328  uint8_t using_interlock : 1; // 20 // aux switch motor interlock function is in use
329  uint8_t motor_emergency_stop : 1; // 21 // motor estop switch, shuts off motors when enabled
330  uint8_t land_repo_active : 1; // 22 // true if the pilot is overriding the landing position
331  uint8_t motor_interlock_switch : 1; // 23 // true if pilot is requesting motor interlock enable
332  uint8_t in_arming_delay : 1; // 24 // true while we are armed but waiting to spin motors
333  uint8_t initialised_params : 1; // 25 // true when the all parameters have been initialised. we cannot send parameters to the GCS until this is done
334  uint8_t compass_init_location : 1; // 26 // true when the compass's initial location has been set
335  uint8_t rc_override_enable : 1; // 27 // aux switch rc_override is allowed
336  };
337  uint32_t value;
338  } ap_t;
339 
340  ap_t ap;
341 
342  // This is the state of the flight control system
343  // There are multiple states defined such as STABILIZE, ACRO,
344  control_mode_t control_mode;
345  mode_reason_t control_mode_reason = MODE_REASON_UNKNOWN;
346 
347  control_mode_t prev_control_mode;
348  mode_reason_t prev_control_mode_reason = MODE_REASON_UNKNOWN;
349 
350  // Structure used to detect changes in the flight mode control switch
351  struct {
352  int8_t debounced_switch_position; // currently used switch position
353  int8_t last_switch_position; // switch position in previous iteration
354  uint32_t last_edge_time_ms; // system time that switch position was last changed
355  } control_switch_state;
356 
357  typedef struct {
358  bool running;
359  float max_speed;
360  float alt_delta;
361  uint32_t start_ms;
362  } takeoff_state_t;
363  takeoff_state_t takeoff_state;
364 
365  // altitude below which we do no navigation in auto takeoff
366  float auto_takeoff_no_nav_alt_cm;
367 
368  RCMapper rcmap;
369 
370  // intertial nav alt when we armed
371  float arming_altitude_m;
372 
373  // board specific config
374  AP_BoardConfig BoardConfig;
375 
376 #if HAL_WITH_UAVCAN
377  // board specific config for CAN bus
378  AP_BoardConfig_CAN BoardConfig_CAN;
379 #endif
380 
381  // Failsafe
382  struct {
383  uint32_t last_heartbeat_ms; // the time when the last HEARTBEAT message arrived from a GCS - used for triggering gcs failsafe
384  uint32_t terrain_first_failure_ms; // the first time terrain data access failed - used to calculate the duration of the failure
385  uint32_t terrain_last_failure_ms; // the most recent time terrain data access failed
386 
387  int8_t radio_counter; // number of iterations with throttle below throttle_fs_value
388 
389  uint8_t rc_override_active : 1; // true if rc control are overwritten by ground station
390  uint8_t radio : 1; // A status flag for the radio failsafe
391  uint8_t gcs : 1; // A status flag for the ground station failsafe
392  uint8_t ekf : 1; // true if ekf failsafe has occurred
393  uint8_t terrain : 1; // true if the missing terrain data failsafe has occurred
394  uint8_t adsb : 1; // true if an adsb related failsafe has occurred
395  } failsafe;
396 
397  bool any_failsafe_triggered() const {
398  return failsafe.radio || battery.has_failsafed() || failsafe.gcs || failsafe.ekf || failsafe.terrain || failsafe.adsb;
399  }
400 
401  // sensor health for logging
402  struct {
403  uint8_t baro : 1; // true if baro is healthy
404  uint8_t compass : 1; // true if compass is healthy
405  uint8_t primary_gps : 2; // primary gps index
406  } sensor_health;
407 
408  // Motor Output
409 #if FRAME_CONFIG == HELI_FRAME
410  #define MOTOR_CLASS AP_MotorsHeli
411 #else
412  #define MOTOR_CLASS AP_MotorsMulticopter
413 #endif
414 
415  MOTOR_CLASS *motors;
416  const struct AP_Param::GroupInfo *motors_var_info;
417 
418  // GPS variables
419  // Sometimes we need to remove the scaling for distance calcs
420  float scaleLongDown;
421 
422  int32_t _home_bearing;
423  uint32_t _home_distance;
424 
425  // SIMPLE Mode
426  // Used to track the orientation of the vehicle for Simple mode. This value is reset at each arming
427  // or in SuperSimple mode when the vehicle leaves a 20m radius from home.
428  float simple_cos_yaw;
429  float simple_sin_yaw;
430  int32_t super_simple_last_bearing;
431  float super_simple_cos_yaw;
432  float super_simple_sin_yaw;
433 
434  // Stores initial bearing when armed - initial simple bearing is modified in super simple mode so not suitable
435  int32_t initial_armed_bearing;
436 
437  // Battery Sensors
438  AP_BattMonitor battery{MASK_LOG_CURRENT,
439  FUNCTOR_BIND_MEMBER(&Copter::handle_battery_failsafe, void, const char*, const int8_t),
440  _failsafe_priorities};
441 
442 #if FRSKY_TELEM_ENABLED == ENABLED
443  // FrSky telemetry support
444  AP_Frsky_Telem frsky_telemetry{ahrs, battery, rangefinder};
445 #endif
446 #if DEVO_TELEM_ENABLED == ENABLED
447  AP_DEVO_Telem devo_telemetry{ahrs};
448 #endif
449 
450  // Variables for extended status MAVLink messages
451  uint32_t control_sensors_present;
452  uint32_t control_sensors_enabled;
453  uint32_t control_sensors_health;
454 
455  // Altitude
456  // The cm/s we are moving up or down based on filtered data - Positive = UP
457  int16_t climb_rate;
458  float target_rangefinder_alt; // desired altitude in cm above the ground
459  int32_t baro_alt; // barometer altitude in cm above home
460  float baro_climbrate; // barometer climbrate in cm/s
461  LowPassFilterVector3f land_accel_ef_filter; // accelerations for land and crash detector tests
462 
463  // filtered pilot's throttle input used to cancel landing if throttle held high
464  LowPassFilterFloat rc_throttle_control_in_filter;
465 
466  // 3D Location vectors
467  // Current location of the vehicle (altitude is relative to home)
468  Location_Class current_loc;
469 
470  // IMU variables
471  // Integration time (in seconds) for the gyros (DCM algorithm)
472  // Updated with the fast loop
473  float G_Dt;
474 
475  // Inertial Navigation
476  AP_InertialNav_NavEKF inertial_nav;
477 
478  // Attitude, Position and Waypoint navigation objects
479  // To-Do: move inertial nav up or other navigation variables down here
480 #if FRAME_CONFIG == HELI_FRAME
481  #define AC_AttitudeControl_t AC_AttitudeControl_Heli
482 #else
483  #define AC_AttitudeControl_t AC_AttitudeControl_Multi
484 #endif
485  AC_AttitudeControl_t *attitude_control;
486  AC_PosControl *pos_control;
487  AC_WPNav *wp_nav;
488  AC_Loiter *loiter_nav;
489 #if MODE_CIRCLE_ENABLED == ENABLED
490  AC_Circle *circle_nav;
491 #endif
492 
493  // System Timers
494  // --------------
495  // arm_time_ms - Records when vehicle was armed. Will be Zero if we are disarmed.
496  uint32_t arm_time_ms;
497 
498  // Used to exit the roll and pitch auto trim function
499  uint8_t auto_trim_counter;
500 
501  // Reference to the relay object
502  AP_Relay relay;
503 
504  // handle repeated servo and relay events
505  AP_ServoRelayEvents ServoRelayEvents{relay};
506 
507  // Camera
508 #if CAMERA == ENABLED
509  AP_Camera camera{&relay, MASK_LOG_CAMERA, current_loc, ahrs};
510 #endif
511 
512  // Camera/Antenna mount tracking and stabilisation stuff
513 #if MOUNT == ENABLED
514  // current_loc uses the baro/gps solution for altitude rather than gps only.
515  AP_Mount camera_mount{ahrs, current_loc};
516 #endif
517 
518  // AC_Fence library to reduce fly-aways
519 #if AC_FENCE == ENABLED
520  AC_Fence fence{ahrs};
521 #endif
522 
523 #if AC_AVOID_ENABLED == ENABLED
524 # if BEACON_ENABLED == ENABLED
525  AC_Avoid avoid{ahrs, fence, g2.proximity, &g2.beacon};
526 # else
527  AC_Avoid avoid{ahrs, fence, g2.proximity};
528 # endif
529 #endif
530 
531  // Rally library
532 #if AC_RALLY == ENABLED
533  AP_Rally_Copter rally{ahrs};
534 #endif
535 
536  // RSSI
537  AP_RSSI rssi;
538 
539  // Crop Sprayer
540 #if SPRAYER == ENABLED
541  AC_Sprayer sprayer;
542 #endif
543 
544  // Parachute release
545 #if PARACHUTE == ENABLED
546  AP_Parachute parachute{relay};
547 #endif
548 
549  // Landing Gear Controller
550  AP_LandingGear landinggear;
551 
552  // terrain handling
553 #if AP_TERRAIN_AVAILABLE && AC_TERRAIN
554  AP_Terrain terrain{ahrs, mission, rally};
555 #endif
556 
557  // Precision Landing
558 #if PRECISION_LANDING == ENABLED
559  AC_PrecLand precland{ahrs};
560 #endif
561 
562  // Pilot Input Management Library
563  // Only used for Helicopter for now
564 #if FRAME_CONFIG == HELI_FRAME
565  AC_InputManager_Heli input_manager;
566 #endif
567 
568 #if ADSB_ENABLED == ENABLED
569  AP_ADSB adsb;
570 
571  // avoidance of adsb enabled vehicles (normally manned vehicles)
572  AP_Avoidance_Copter avoidance_adsb{ahrs, adsb};
573 #endif
574 
575  // last valid RC input time
576  uint32_t last_radio_update_ms;
577 
578  // last esc calibration notification update
579  uint32_t esc_calibration_notify_update_ms;
580 
581 #if VISUAL_ODOMETRY_ENABLED == ENABLED
582  // last visual odometry update time
583  uint32_t visual_odom_last_update_ms;
584 #endif
585 
586  // Top-level logic
587  // setup the var_info table
588  AP_Param param_loader;
589 
590 #if FRAME_CONFIG == HELI_FRAME
591  // Mode filter to reject RC Input glitches. Filter size is 5, and it draws the 4th element, so it can reject 3 low glitches,
592  // and 1 high glitch. This is because any "off" glitches can be highly problematic for a helicopter running an ESC
593  // governor. Even a single "off" frame can cause the rotor to slow dramatically and take a long time to restart.
594  ModeFilterInt16_Size5 rotor_speed_deglitch_filter {4};
595 
596  // Tradheli flags
597  typedef struct {
598  uint8_t dynamic_flight : 1; // 0 // true if we are moving at a significant speed (used to turn on/off leaky I terms)
599  uint8_t init_targets_on_arming : 1; // 1 // true if we have been disarmed, and need to reset rate controller targets when we arm
600  uint8_t inverted_flight : 1; // 2 // true for inverted flight mode
601  } heli_flags_t;
602  heli_flags_t heli_flags;
603 
604  int16_t hover_roll_trim_scalar_slew;
605 #endif
606 
607  // ground effect detector
608  struct {
611  uint32_t takeoff_time_ms;
613  } gndeffect_state;
614 
615  // set when we are upgrading parameters from 3.4
616  bool upgrading_frame_params;
617 
618  static const AP_Scheduler::Task scheduler_tasks[];
619  static const AP_Param::Info var_info[];
620  static const struct LogStructure log_structure[];
621 
622  enum Failsafe_Action {
623  Failsafe_Action_None = 0,
624  Failsafe_Action_Land = 1,
625  Failsafe_Action_RTL = 2,
626  Failsafe_Action_SmartRTL = 3,
627  Failsafe_Action_SmartRTL_Land = 4,
628  Failsafe_Action_Terminate = 5
629  };
630 
631  static constexpr int8_t _failsafe_priorities[] = {
632  Failsafe_Action_Terminate,
633  Failsafe_Action_Land,
634  Failsafe_Action_RTL,
635  Failsafe_Action_SmartRTL_Land,
636  Failsafe_Action_SmartRTL,
637  Failsafe_Action_None,
638  -1 // the priority list must end with a sentinel of -1
639  };
640 
641  #define FAILSAFE_LAND_PRIORITY 1
642  static_assert(_failsafe_priorities[FAILSAFE_LAND_PRIORITY] == Failsafe_Action_Land,
643  "FAILSAFE_LAND_PRIORITY must match the entry in _failsafe_priorities");
644  static_assert(_failsafe_priorities[ARRAY_SIZE(_failsafe_priorities) - 1] == -1,
645  "_failsafe_priorities is missing the sentinel");
646 
647 
648 
649  // AP_State.cpp
650  void set_auto_armed(bool b);
651  void set_simple_mode(uint8_t b);
652  void set_failsafe_radio(bool b);
653  void set_failsafe_gcs(bool b);
654  void update_using_interlock();
655  void set_motor_emergency_stop(bool b);
656 
657  // ArduCopter.cpp
658  void fast_loop();
659  void rc_loop();
660  void throttle_loop();
661  void update_batt_compass(void);
662  void fourhundred_hz_logging();
663  void ten_hz_logging_loop();
664  void twentyfive_hz_logging();
665  void three_hz_loop();
666  void one_hz_loop();
667  void update_GPS(void);
668  void init_simple_bearing();
669  void update_simple_mode(void);
670  void update_super_simple_bearing(bool force_update);
671  void read_AHRS(void);
672  void update_altitude();
673 
674  // Attitude.cpp
675  float get_pilot_desired_yaw_rate(int16_t stick_angle);
676  void update_throttle_hover();
677  void set_throttle_takeoff();
678  float get_pilot_desired_throttle(int16_t throttle_control, float thr_mid = 0.0f);
679  float get_pilot_desired_climb_rate(float throttle_control);
680  float get_non_takeoff_throttle();
681  float get_surface_tracking_climb_rate(int16_t target_rate, float current_alt_target, float dt);
682  float get_avoidance_adjusted_climbrate(float target_rate);
683  void set_accel_throttle_I_from_pilot_throttle();
684  void rotate_body_frame_to_NE(float &x, float &y);
685  uint16_t get_pilot_speed_dn();
686 
687 #if ADSB_ENABLED == ENABLED
688  // avoidance_adsb.cpp
689  void avoidance_adsb_update(void);
690 #endif
691 
692  // baro_ground_effect.cpp
693  void update_ground_effect_detector(void);
694 
695  // capabilities.cpp
696  void init_capabilities(void);
697 
698  // commands.cpp
699  void update_home_from_EKF();
700  void set_home_to_current_location_inflight();
701  bool set_home_to_current_location(bool lock);
702  bool set_home(const Location& loc, bool lock);
703  bool far_from_EKF_origin(const Location& loc);
704  void set_system_time_from_GPS();
705 
706  // compassmot.cpp
707  MAV_RESULT mavlink_compassmot(mavlink_channel_t chan);
708 
709  // compat.cpp
710  void delay(uint32_t ms);
711 
712  // crash_check.cpp
713  void crash_check();
714  void parachute_check();
715  void parachute_release();
716  void parachute_manual_release();
717 
718  // ekf_check.cpp
719  void ekf_check();
720  bool ekf_over_threshold();
721  void failsafe_ekf_event();
722  void failsafe_ekf_off_event(void);
723  void check_ekf_reset();
724 
725  // esc_calibration.cpp
726  void esc_calibration_startup_check();
727  void esc_calibration_passthrough();
728  void esc_calibration_auto();
729  void esc_calibration_notify();
730 
731  // events.cpp
732  void failsafe_radio_on_event();
733  void failsafe_radio_off_event();
734  void handle_battery_failsafe(const char* type_str, const int8_t action);
735  void failsafe_gcs_check();
736  void failsafe_gcs_off_event(void);
737  void failsafe_terrain_check();
738  void failsafe_terrain_set_status(bool data_ok);
739  void failsafe_terrain_on_event();
740  void gpsglitch_check();
741  void set_mode_RTL_or_land_with_pause(mode_reason_t reason);
742  void set_mode_SmartRTL_or_RTL(mode_reason_t reason);
743  void set_mode_SmartRTL_or_land_with_pause(mode_reason_t reason);
744  bool should_disarm_on_failsafe();
745  void update_events();
746 
747  // failsafe.cpp
748  void failsafe_enable();
749  void failsafe_disable();
750 #if ADVANCED_FAILSAFE == ENABLED
751  void afs_fs_check(void);
752 #endif
753 
754  // fence.cpp
755  void fence_check();
756  void fence_send_mavlink_status(mavlink_channel_t chan);
757 
758  // GCS_Mavlink.cpp
759  void gcs_send_heartbeat(void);
760  void gcs_send_deferred(void);
761  void send_fence_status(mavlink_channel_t chan);
762  void send_extended_status1(mavlink_channel_t chan);
763  void send_nav_controller_output(mavlink_channel_t chan);
764  void send_vfr_hud(mavlink_channel_t chan);
765  void send_rpm(mavlink_channel_t chan);
766  void send_pid_tuning(mavlink_channel_t chan);
767  void gcs_data_stream_send(void);
768  void gcs_check_input(void);
769 
770  // heli.cpp
771  void heli_init();
772  void check_dynamic_flight(void);
773  void update_heli_control_dynamics(void);
774  void heli_update_landing_swash();
775  void heli_update_rotor_speed_targets();
776 
777  // inertia.cpp
778  void read_inertia();
779 
780  // landing_detector.cpp
781  void update_land_and_crash_detectors();
782  void update_land_detector();
783  void set_land_complete(bool b);
784  void set_land_complete_maybe(bool b);
785  void update_throttle_thr_mix();
786 
787  // landing_gear.cpp
788  void landinggear_update();
789 
790  // Log.cpp
791  void Log_Write_Optflow();
792  void Log_Write_Control_Tuning();
793  void Log_Write_Performance();
794  void Log_Write_Attitude();
795  void Log_Write_EKF_POS();
796  void Log_Write_MotBatt();
797  void Log_Write_Event(uint8_t id);
798  void Log_Write_Data(uint8_t id, int32_t value);
799  void Log_Write_Data(uint8_t id, uint32_t value);
800  void Log_Write_Data(uint8_t id, int16_t value);
801  void Log_Write_Data(uint8_t id, uint16_t value);
802  void Log_Write_Data(uint8_t id, float value);
803  void Log_Write_Error(uint8_t sub_system, uint8_t error_code);
804  void Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, int16_t control_in, int16_t tune_low, int16_t tune_high);
805  void Log_Sensor_Health();
806 #if FRAME_CONFIG == HELI_FRAME
807  void Log_Write_Heli(void);
808 #endif
809  void Log_Write_Precland();
810  void Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target, const Vector3f& vel_target);
811  void Log_Write_Vehicle_Startup_Messages();
812  void log_init(void);
813 
814  // mode.cpp
815  bool set_mode(control_mode_t mode, mode_reason_t reason);
816  void update_flight_mode();
817  void notify_flight_mode();
818 
819  // mode_land.cpp
820  void set_mode_land_with_pause(mode_reason_t reason);
821  bool landing_with_GPS();
822 
823  // motor_test.cpp
824  void motor_test_output();
825  bool mavlink_motor_test_check(mavlink_channel_t chan, bool check_rc);
826  MAV_RESULT mavlink_motor_test_start(mavlink_channel_t chan, uint8_t motor_seq, uint8_t throttle_type, uint16_t throttle_value, float timeout_sec, uint8_t motor_count);
827  void motor_test_stop();
828 
829  // motors.cpp
830  void arm_motors_check();
831  void auto_disarm_check();
832  bool init_arm_motors(bool arming_from_gcs);
833  void init_disarm_motors();
834  void motors_output();
835  void lost_vehicle_check();
836 
837  // navigation.cpp
838  void run_nav_updates(void);
839  int32_t home_bearing();
840  uint32_t home_distance();
841 
842  // Parameters.cpp
843  void load_parameters(void);
844  void convert_pid_parameters(void);
845 
846  // position_vector.cpp
847  Vector3f pv_location_to_vector(const Location& loc);
848  float pv_alt_above_origin(float alt_above_home_cm);
849  float pv_alt_above_home(float alt_above_origin_cm);
850  float pv_distance_to_home_cm(const Vector3f &destination);
851 
852  // precision_landing.cpp
853  void init_precland();
854  void update_precland();
855 
856  // radio.cpp
857  void default_dead_zones();
858  void init_rc_in();
859  void init_rc_out();
860  void enable_motor_output();
861  void read_radio();
862  void set_throttle_and_failsafe(uint16_t throttle_pwm);
863  void set_throttle_zero_flag(int16_t throttle_control);
864  void radio_passthrough_to_motors();
865  int16_t get_throttle_mid(void);
866 
867  // sensors.cpp
868  void read_barometer(void);
869  void init_rangefinder(void);
870  void read_rangefinder(void);
871  bool rangefinder_alt_ok();
872  void rpm_update();
873  void init_compass();
874  void compass_accumulate(void);
875  void init_optflow();
876  void update_optical_flow(void);
877  void compass_cal_update(void);
878  void accel_cal_update(void);
879  void init_proximity();
880  void update_proximity();
881  void update_sensor_status_flags(void);
882  void init_visual_odom();
883  void update_visual_odom();
884  void winch_init();
885  void winch_update();
886 
887  // setup.cpp
888  void report_compass();
889  void print_blanks(int16_t num);
890  void print_divider(void);
891  void print_enabled(bool b);
892  void report_version();
893 
894  // switches.cpp
895  void read_control_switch();
896  bool check_if_auxsw_mode_used(uint8_t auxsw_mode_check);
897  bool check_duplicate_auxsw(void);
898  void reset_control_switch();
899  uint8_t read_3pos_switch(uint8_t chan);
900  void read_aux_switches();
901  void init_aux_switches();
902  void init_aux_switch_function(int8_t ch_option, uint8_t ch_flag);
903  void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag);
904  void save_trim();
905  void auto_trim();
906 
907  // system.cpp
908  void init_ardupilot();
909  void startup_INS_ground();
910  bool position_ok();
911  bool ekf_position_ok();
912  bool optflow_position_ok();
913  void update_auto_armed();
914  void check_usb_mux(void);
915  bool should_log(uint32_t mask);
916  void set_default_frame_class();
917  MAV_TYPE get_frame_mav_type();
918  const char* get_frame_string();
919  void allocate_motors(void);
920 
921  // takeoff.cpp
922  bool current_mode_has_user_takeoff(bool must_navigate);
923  bool do_user_takeoff(float takeoff_alt_cm, bool must_navigate);
924  void takeoff_timer_start(float alt_cm);
925  void takeoff_stop();
926  void takeoff_get_climb_rates(float& pilot_climb_rate, float& takeoff_climb_rate);
927  void auto_takeoff_set_start_alt(void);
928  void auto_takeoff_attitude_run(float target_yaw_rate);
929 
930  // terrain.cpp
931  void terrain_update();
932  void terrain_logging();
933  bool terrain_use();
934 
935  // tuning.cpp
936  void tuning();
937 
938  // UserCode.cpp
939  void userhook_init();
940  void userhook_FastLoop();
941  void userhook_50Hz();
942  void userhook_MediumLoop();
943  void userhook_SlowLoop();
944  void userhook_SuperSlowLoop();
945 
946 #include "mode.h"
947 
948  Mode *flightmode;
949 #if MODE_ACRO_ENABLED == ENABLED
950 #if FRAME_CONFIG == HELI_FRAME
951  ModeAcro_Heli mode_acro;
952 #else
953  ModeAcro mode_acro;
954 #endif
955 #endif
956  ModeAltHold mode_althold;
957 #if MODE_AUTO_ENABLED == ENABLED
958  ModeAuto mode_auto;
959 #endif
960 #if AUTOTUNE_ENABLED == ENABLED
961  ModeAutoTune mode_autotune;
962 #endif
963 #if MODE_BRAKE_ENABLED == ENABLED
964  ModeBrake mode_brake;
965 #endif
966 #if MODE_CIRCLE_ENABLED == ENABLED
967  ModeCircle mode_circle;
968 #endif
969 #if MODE_DRIFT_ENABLED == ENABLED
970  ModeDrift mode_drift;
971 #endif
972  ModeFlip mode_flip;
973 #if MODE_FOLLOW_ENABLED == ENABLED
974  ModeFollow mode_follow;
975 #endif
976 #if MODE_GUIDED_ENABLED == ENABLED
977  ModeGuided mode_guided;
978 #endif
979  ModeLand mode_land;
980 #if MODE_LOITER_ENABLED == ENABLED
981  ModeLoiter mode_loiter;
982 #endif
983 #if MODE_POSHOLD_ENABLED == ENABLED
984  ModePosHold mode_poshold;
985 #endif
986 #if MODE_RTL_ENABLED == ENABLED
987  ModeRTL mode_rtl;
988 #endif
989 #if FRAME_CONFIG == HELI_FRAME
990  ModeStabilize_Heli mode_stabilize;
991 #else
992  ModeStabilize mode_stabilize;
993 #endif
994 #if MODE_SPORT_ENABLED == ENABLED
995  ModeSport mode_sport;
996 #endif
997 #if ADSB_ENABLED == ENABLED
998  ModeAvoidADSB mode_avoid_adsb;
999 #endif
1000 #if MODE_THROW_ENABLED == ENABLED
1001  ModeThrow mode_throw;
1002 #endif
1003 #if MODE_GUIDED_NOGPS_ENABLED == ENABLED
1004  ModeGuidedNoGPS mode_guided_nogps;
1005 #endif
1006 #if MODE_SMARTRTL_ENABLED == ENABLED
1007  ModeSmartRTL mode_smartrtl;
1008 #endif
1009 #if !HAL_MINIMIZE_FEATURES && OPTFLOW == ENABLED
1010  ModeFlowHold mode_flowhold;
1011 #endif
1012 
1013  // mode.cpp
1014  Mode *mode_from_mode_num(const uint8_t mode);
1015  void exit_mode(Mode *&old_flightmode, Mode *&new_flightmode);
1016 
1017 public:
1018  void mavlink_delay_cb(); // GCS_Mavlink.cpp
1019  void failsafe_check(); // failsafe.cpp
1020 };
1021 
1022 extern const AP_HAL::HAL& hal;
1023 extern Copter copter;
1024 
1025 using AP_HAL::millis;
1026 using AP_HAL::micros;
Definition: mode.h:5
uint32_t terrain_last_failure_ms
Definition: Copter.h:385
Definition: mode.h:1057
Copter(void)
Definition: Copter.cpp:26
void failsafe_check()
Definition: failsafe.cpp:35
const AP_HAL::HAL & hal
Definition: Copter.cpp:21
float takeoff_alt_cm
Definition: Copter.h:612
uint8_t terrain
Definition: Copter.h:393
Definition: mode.h:547
uint32_t last_healthy_ms
Definition: Copter.h:243
Definition: mode.h:997
int8_t last_switch_position
Definition: Copter.h:353
void mavlink_delay_cb()
Definition: GCS_Mavlink.cpp:1606
control_mode_t
Definition: defines.h:91
Definition: toy_mode.h:8
Definition: GCS_Copter.h:6
#define AC_AttitudeControl_t
Definition: Copter.h:483
Definition: mode.h:167
Definition: mode.h:1033
uint8_t radio
Definition: Copter.h:390
Definition: Parameters.h:7
int8_t debounced_switch_position
Definition: Copter.h:352
uint32_t last_edge_time_ms
Definition: Copter.h:354
#define FAILSAFE_LAND_PRIORITY
Definition: Copter.h:641
Definition: mode.h:742
Definition: mode.h:194
AP_Beacon beacon
Definition: Parameters.h:529
LowPassFilterFloat alt_cm_filt
Definition: Copter.h:244
uint8_t compass
Definition: Copter.h:404
mode_reason_t
Definition: defines.h:115
Definition: mode.h:1174
Definition: Parameters.h:493
Definition: mode.h:664
#define MASK_LOG_CURRENT
Definition: defines.h:323
Definition: mode.h:927
bool alt_healthy
Definition: Copter.h:241
Definition: mode.h:895
Definition: mode.h:576
Definition: mode.h:855
Definition: mode.h:1098
Definition: mode.h:1081
Definition: mode.h:826
uint8_t ekf
Definition: Copter.h:392
Definition: mode.h:605
Definition: AP_Rally.h:20
int16_t alt_cm
Definition: Copter.h:242
uint8_t baro
Definition: Copter.h:403
uint8_t adsb
Definition: Copter.h:394
Definition: avoidance_adsb.h:9
uint8_t gcs
Definition: Copter.h:391
uint8_t primary_gps
Definition: Copter.h:405
Definition: afs_copter.h:27
uint8_t rc_override_active
Definition: Copter.h:389
Definition: mode.h:631
void setup() override
Definition: ArduCopter.cpp:197
Definition: mode.h:802
Definition: defines.h:116
bool touchdown_expected
Definition: Copter.h:610
Definition: mode.h:209
bool takeoff_expected
Definition: Copter.h:609
uint32_t takeoff_time_ms
Definition: Copter.h:611
Copter copter
Definition: ArduCopter.cpp:581
Definition: mode.h:392
Definition: mode.h:233
void loop() override
Definition: ArduCopter.cpp:211
uint32_t terrain_first_failure_ms
Definition: Copter.h:384
Definition: AP_Arming.h:5
#define MASK_LOG_CAMERA
Definition: defines.h:329
Definition: Copter.h:180
Definition: mode.h:1149
bool enabled
Definition: Copter.h:240
#define MOTOR_CLASS
Definition: Copter.h:412
AP_Proximity proximity
Definition: Parameters.h:539
int8_t radio_counter
Definition: Copter.h:387
int8_t glitch_count
Definition: Copter.h:245
uint32_t last_heartbeat_ms
Definition: Copter.h:383
Definition: GCS_Mavlink.h:8