28 #include <AP_HAL/AP_HAL.h> 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> 37 #include <GCS_MAVLink/GCS.h> 38 #include <AP_SerialManager/AP_SerialManager.h> 39 #include <AP_GPS/AP_GPS.h> 40 #include <DataFlash/DataFlash.h> 41 #include <AP_ADC/AP_ADC.h> 42 #include <AP_Baro/AP_Baro.h> 43 #include <AP_Compass/AP_Compass.h> 44 #include <AP_Math/AP_Math.h> 45 #include <AP_AccelCal/AP_AccelCal.h> 46 #include <AP_InertialSensor/AP_InertialSensor.h> 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> 51 #include <AC_PID/AC_P.h> 52 #include <AC_PID/AC_PID.h> 53 #include <AC_PID/AC_PI_2D.h> 54 #include <AC_PID/AC_PID_2D.h> 55 #include <AC_PID/AC_HELI_PID.h> 56 #include <AC_AttitudeControl/AC_AttitudeControl_Multi.h> 57 #include <AC_AttitudeControl/AC_AttitudeControl_Heli.h> 58 #include <AC_AttitudeControl/AC_PosControl.h> 59 #include <RC_Channel/RC_Channel.h> 60 #include <AP_Motors/AP_Motors.h> 61 #include <AP_Stats/AP_Stats.h> 62 #include <AP_RSSI/AP_RSSI.h> 63 #include <Filter/Filter.h> 64 #include <AP_Buffer/AP_Buffer.h> 65 #include <AP_Relay/AP_Relay.h> 66 #include <AP_ServoRelayEvents/AP_ServoRelayEvents.h> 67 #include <AP_Airspeed/AP_Airspeed.h> 68 #include <AP_Vehicle/AP_Vehicle.h> 69 #include <AP_InertialNav/AP_InertialNav.h> 70 #include <AC_WPNav/AC_WPNav.h> 71 #include <AC_WPNav/AC_Loiter.h> 72 #include <AC_WPNav/AC_Circle.h> 73 #include <AP_Declination/AP_Declination.h> 74 #include <AP_Scheduler/AP_Scheduler.h> 75 #include <AP_RCMapper/AP_RCMapper.h> 76 #include <AP_Notify/AP_Notify.h> 77 #include <AP_BattMonitor/AP_BattMonitor.h> 78 #include <AP_BoardConfig/AP_BoardConfig.h> 79 #include <AP_BoardConfig/AP_BoardConfig_CAN.h> 80 #include <AP_LandingGear/AP_LandingGear.h> 81 #include <AC_InputManager/AC_InputManager.h> 82 #include <AC_InputManager/AC_InputManager_Heli.h> 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> 98 #if BEACON_ENABLED == ENABLED 99 #include <AP_Beacon/AP_Beacon.h> 101 #if AC_AVOID_ENABLED == ENABLED 102 #include <AC_Avoidance/AC_Avoid.h> 104 #if SPRAYER == ENABLED 105 # include <AC_Sprayer/AC_Sprayer.h> 107 #if GRIPPER_ENABLED == ENABLED 108 # include <AP_Gripper/AP_Gripper.h> 110 #if PARACHUTE == ENABLED 111 # include <AP_Parachute/AP_Parachute.h> 113 #if PRECISION_LANDING == ENABLED 114 # include <AC_PrecLand/AC_PrecLand.h> 115 # include <AP_IRLock/AP_IRLock.h> 117 #if FRSKY_TELEM_ENABLED == ENABLED 118 # include <AP_Frsky_Telem/AP_Frsky_Telem.h> 120 #if ADSB_ENABLED == ENABLED 121 # include <AP_ADSB/AP_ADSB.h> 123 #if MODE_FOLLOW_ENABLED == ENABLED 124 # include <AP_Follow/AP_Follow.h> 126 #if AC_FENCE == ENABLED 127 # include <AC_Fence/AC_Fence.h> 129 #if AC_TERRAIN == ENABLED 130 # include <AP_Terrain/AP_Terrain.h> 132 #if OPTFLOW == ENABLED 133 # include <AP_OpticalFlow/AP_OpticalFlow.h> 135 #if VISUAL_ODOMETRY_ENABLED == ENABLED 136 # include <AP_VisualOdom/AP_VisualOdom.h> 138 #if RANGEFINDER_ENABLED == ENABLED 139 # include <AP_RangeFinder/AP_RangeFinder.h> 141 #if PROXIMITY_ENABLED == ENABLED 142 # include <AP_Proximity/AP_Proximity.h> 145 #include <AP_Mount/AP_Mount.h> 147 #if CAMERA == ENABLED 148 # include <AP_Camera/AP_Camera.h> 151 #if DEVO_TELEM_ENABLED == ENABLED 152 #include <AP_Devo_Telem/AP_Devo_Telem.h> 155 #if ADVANCED_FAILSAFE == ENABLED 158 #if TOY_MODE_ENABLED == ENABLED 161 #if WINCH_ENABLED == ENABLED 162 # include <AP_WheelEncoder/AP_WheelEncoder.h> 163 # include <AP_Winch/AP_Winch.h> 165 #if RPM_ENABLED == ENABLED 166 #include <AP_RPM/AP_RPM.h> 171 #if ADSB_ENABLED == ENABLED 175 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 176 #include <SITL/SITL.h> 180 class Copter :
public AP_HAL::HAL::Callbacks {
189 #if ADVANCED_FAILSAFE == ENABLED 198 void setup()
override;
199 void loop()
override;
202 static const AP_FWVersion fwver;
205 AP_Vehicle::MultiCopter aparm;
212 AP_Scheduler scheduler{FUNCTOR_BIND_MEMBER(&Copter::fast_loop,
void)};
218 uint8_t command_ack_counter;
221 RC_Channel *channel_roll;
222 RC_Channel *channel_pitch;
223 RC_Channel *channel_throttle;
224 RC_Channel *channel_yaw;
227 DataFlash_Class DataFlash;
232 AP_Int8 *flight_modes;
236 AP_InertialSensor ins;
238 RangeFinder rangefinder{serial_manager, ROTATION_PITCH_270};
246 } rangefinder_state = {
false,
false, 0, 0 };
248 #if RPM_ENABLED == ENABLED 253 NavEKF2 EKF2{&ahrs, rangefinder};
254 NavEKF3 EKF3{&ahrs, rangefinder};
255 AP_AHRS_NavEKF ahrs{EKF2, EKF3, AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF};
257 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 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)};
268 bool start_command(
const AP_Mission::Mission_Command& cmd) {
269 return mode_auto.start_command(cmd);
271 bool verify_command_callback(
const AP_Mission::Mission_Command& cmd) {
272 return mode_auto.verify_command_callback(cmd);
274 void exit_mission() {
275 mode_auto.exit_mission();
283 #if OPTFLOW == ENABLED 284 OpticalFlow optflow{ahrs};
288 float ekfGndSpdLimit;
291 float ekfNavVelGainScaler;
294 uint32_t ekfYawReset_ms;
295 int8_t ekf_primary_core;
297 AP_SerialManager serial_manager;
304 #ifdef USERHOOK_VARIABLES 305 # include USERHOOK_VARIABLES 312 uint8_t simple_mode : 2;
313 uint8_t pre_arm_rc_check : 1;
314 uint8_t pre_arm_check : 1;
315 uint8_t auto_armed : 1;
316 uint8_t logging_started : 1;
317 uint8_t land_complete : 1;
318 uint8_t new_radio_frame : 1;
319 uint8_t usb_connected : 1;
320 uint8_t rc_receiver_present : 1;
321 uint8_t compass_mot : 1;
322 uint8_t motor_test : 1;
323 uint8_t initialised : 1;
324 uint8_t land_complete_maybe : 1;
325 uint8_t throttle_zero : 1;
326 uint8_t system_time_set : 1;
327 uint8_t gps_glitching : 1;
328 uint8_t using_interlock : 1;
329 uint8_t motor_emergency_stop : 1;
330 uint8_t land_repo_active : 1;
331 uint8_t motor_interlock_switch : 1;
332 uint8_t in_arming_delay : 1;
333 uint8_t initialised_params : 1;
334 uint8_t compass_init_location : 1;
335 uint8_t rc_override_enable : 1;
355 } control_switch_state;
363 takeoff_state_t takeoff_state;
366 float auto_takeoff_no_nav_alt_cm;
371 float arming_altitude_m;
374 AP_BoardConfig BoardConfig;
378 AP_BoardConfig_CAN BoardConfig_CAN;
397 bool any_failsafe_triggered()
const {
398 return failsafe.radio || battery.has_failsafed() || failsafe.gcs || failsafe.ekf || failsafe.terrain || failsafe.adsb;
409 #if FRAME_CONFIG == HELI_FRAME 410 #define MOTOR_CLASS AP_MotorsHeli 412 #define MOTOR_CLASS AP_MotorsMulticopter 416 const struct AP_Param::GroupInfo *motors_var_info;
422 int32_t _home_bearing;
423 uint32_t _home_distance;
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;
435 int32_t initial_armed_bearing;
439 FUNCTOR_BIND_MEMBER(&Copter::handle_battery_failsafe,
void,
const char*,
const int8_t),
440 _failsafe_priorities};
442 #if FRSKY_TELEM_ENABLED == ENABLED 444 AP_Frsky_Telem frsky_telemetry{ahrs, battery, rangefinder};
446 #if DEVO_TELEM_ENABLED == ENABLED 447 AP_DEVO_Telem devo_telemetry{ahrs};
451 uint32_t control_sensors_present;
452 uint32_t control_sensors_enabled;
453 uint32_t control_sensors_health;
458 float target_rangefinder_alt;
460 float baro_climbrate;
461 LowPassFilterVector3f land_accel_ef_filter;
464 LowPassFilterFloat rc_throttle_control_in_filter;
468 Location_Class current_loc;
476 AP_InertialNav_NavEKF inertial_nav;
480 #if FRAME_CONFIG == HELI_FRAME 481 #define AC_AttitudeControl_t AC_AttitudeControl_Heli 483 #define AC_AttitudeControl_t AC_AttitudeControl_Multi 486 AC_PosControl *pos_control;
488 AC_Loiter *loiter_nav;
489 #if MODE_CIRCLE_ENABLED == ENABLED 490 AC_Circle *circle_nav;
496 uint32_t arm_time_ms;
499 uint8_t auto_trim_counter;
505 AP_ServoRelayEvents ServoRelayEvents{relay};
508 #if CAMERA == ENABLED 515 AP_Mount camera_mount{ahrs, current_loc};
519 #if AC_FENCE == ENABLED 520 AC_Fence fence{ahrs};
523 #if AC_AVOID_ENABLED == ENABLED 524 # if BEACON_ENABLED == ENABLED 527 AC_Avoid avoid{ahrs, fence, g2.
proximity};
532 #if AC_RALLY == ENABLED 540 #if SPRAYER == ENABLED 545 #if PARACHUTE == ENABLED 546 AP_Parachute parachute{relay};
550 AP_LandingGear landinggear;
553 #if AP_TERRAIN_AVAILABLE && AC_TERRAIN 554 AP_Terrain
terrain{ahrs, mission, rally};
558 #if PRECISION_LANDING == ENABLED 559 AC_PrecLand precland{ahrs};
564 #if FRAME_CONFIG == HELI_FRAME 565 AC_InputManager_Heli input_manager;
568 #if ADSB_ENABLED == ENABLED 576 uint32_t last_radio_update_ms;
579 uint32_t esc_calibration_notify_update_ms;
581 #if VISUAL_ODOMETRY_ENABLED == ENABLED 583 uint32_t visual_odom_last_update_ms;
588 AP_Param param_loader;
590 #if FRAME_CONFIG == HELI_FRAME 594 ModeFilterInt16_Size5 rotor_speed_deglitch_filter {4};
598 uint8_t dynamic_flight : 1;
599 uint8_t init_targets_on_arming : 1;
600 uint8_t inverted_flight : 1;
602 heli_flags_t heli_flags;
604 int16_t hover_roll_trim_scalar_slew;
616 bool upgrading_frame_params;
618 static const AP_Scheduler::Task scheduler_tasks[];
619 static const AP_Param::Info var_info[];
620 static const struct LogStructure log_structure[];
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
631 static constexpr int8_t _failsafe_priorities[] = {
632 Failsafe_Action_Terminate,
633 Failsafe_Action_Land,
635 Failsafe_Action_SmartRTL_Land,
636 Failsafe_Action_SmartRTL,
637 Failsafe_Action_None,
641 #define FAILSAFE_LAND_PRIORITY 1 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");
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);
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();
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();
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();
687 #if ADSB_ENABLED == ENABLED 689 void avoidance_adsb_update(
void);
693 void update_ground_effect_detector(
void);
696 void init_capabilities(
void);
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();
707 MAV_RESULT mavlink_compassmot(mavlink_channel_t chan);
710 void delay(uint32_t ms);
714 void parachute_check();
715 void parachute_release();
716 void parachute_manual_release();
720 bool ekf_over_threshold();
721 void failsafe_ekf_event();
722 void failsafe_ekf_off_event(
void);
723 void check_ekf_reset();
726 void esc_calibration_startup_check();
727 void esc_calibration_passthrough();
728 void esc_calibration_auto();
729 void esc_calibration_notify();
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();
743 void set_mode_SmartRTL_or_land_with_pause(
mode_reason_t reason);
744 bool should_disarm_on_failsafe();
745 void update_events();
748 void failsafe_enable();
749 void failsafe_disable();
750 #if ADVANCED_FAILSAFE == ENABLED 751 void afs_fs_check(
void);
756 void fence_send_mavlink_status(mavlink_channel_t chan);
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);
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();
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();
788 void landinggear_update();
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);
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();
816 void update_flight_mode();
817 void notify_flight_mode();
821 bool landing_with_GPS();
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();
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();
838 void run_nav_updates(
void);
839 int32_t home_bearing();
840 uint32_t home_distance();
843 void load_parameters(
void);
844 void convert_pid_parameters(
void);
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);
853 void init_precland();
854 void update_precland();
857 void default_dead_zones();
860 void enable_motor_output();
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);
868 void read_barometer(
void);
869 void init_rangefinder(
void);
870 void read_rangefinder(
void);
871 bool rangefinder_alt_ok();
874 void compass_accumulate(
void);
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();
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();
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);
908 void init_ardupilot();
909 void startup_INS_ground();
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);
922 bool current_mode_has_user_takeoff(
bool must_navigate);
924 void takeoff_timer_start(
float alt_cm);
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);
931 void terrain_update();
932 void terrain_logging();
939 void userhook_init();
940 void userhook_FastLoop();
941 void userhook_50Hz();
942 void userhook_MediumLoop();
943 void userhook_SlowLoop();
944 void userhook_SuperSlowLoop();
949 #if MODE_ACRO_ENABLED == ENABLED 950 #if FRAME_CONFIG == HELI_FRAME 957 #if MODE_AUTO_ENABLED == ENABLED 960 #if AUTOTUNE_ENABLED == ENABLED 963 #if MODE_BRAKE_ENABLED == ENABLED 966 #if MODE_CIRCLE_ENABLED == ENABLED 969 #if MODE_DRIFT_ENABLED == ENABLED 973 #if MODE_FOLLOW_ENABLED == ENABLED 976 #if MODE_GUIDED_ENABLED == ENABLED 980 #if MODE_LOITER_ENABLED == ENABLED 983 #if MODE_POSHOLD_ENABLED == ENABLED 986 #if MODE_RTL_ENABLED == ENABLED 989 #if FRAME_CONFIG == HELI_FRAME 994 #if MODE_SPORT_ENABLED == ENABLED 997 #if ADSB_ENABLED == ENABLED 1000 #if MODE_THROW_ENABLED == ENABLED 1003 #if MODE_GUIDED_NOGPS_ENABLED == ENABLED 1006 #if MODE_SMARTRTL_ENABLED == ENABLED 1009 #if !HAL_MINIMIZE_FEATURES && OPTFLOW == ENABLED 1014 Mode *mode_from_mode_num(
const uint8_t mode);
1015 void exit_mode(
Mode *&old_flightmode,
Mode *&new_flightmode);
1022 extern const AP_HAL::HAL&
hal;
1025 using AP_HAL::millis;
1026 using AP_HAL::micros;
uint32_t terrain_last_failure_ms
Definition: Copter.h:385
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
uint32_t last_healthy_ms
Definition: Copter.h:243
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: GCS_Copter.h:6
#define AC_AttitudeControl_t
Definition: Copter.h:483
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
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: Parameters.h:493
#define MASK_LOG_CURRENT
Definition: defines.h:323
bool alt_healthy
Definition: Copter.h:241
uint8_t ekf
Definition: Copter.h:392
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
void setup() override
Definition: ArduCopter.cpp:197
Definition: defines.h:116
bool touchdown_expected
Definition: Copter.h:610
bool takeoff_expected
Definition: Copter.h:609
uint32_t takeoff_time_ms
Definition: Copter.h:611
Copter copter
Definition: ArduCopter.cpp:581
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
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