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