98 #if BEACON_ENABLED == ENABLED 101 #if AC_AVOID_ENABLED == ENABLED 104 #if SPRAYER == ENABLED 107 #if GRIPPER_ENABLED == ENABLED 110 #if PARACHUTE == ENABLED 113 #if PRECISION_LANDING == ENABLED 117 #if FRSKY_TELEM_ENABLED == ENABLED 120 #if ADSB_ENABLED == ENABLED 123 #if MODE_FOLLOW_ENABLED == ENABLED 126 #if AC_FENCE == ENABLED 129 #if AC_TERRAIN == ENABLED 132 #if OPTFLOW == ENABLED 135 #if VISUAL_ODOMETRY_ENABLED == ENABLED 138 #if RANGEFINDER_ENABLED == ENABLED 141 #if PROXIMITY_ENABLED == ENABLED 147 #if CAMERA == ENABLED 151 #if DEVO_TELEM_ENABLED == ENABLED 155 #if ADVANCED_FAILSAFE == ENABLED 158 #if TOY_MODE_ENABLED == ENABLED 161 #if WINCH_ENABLED == ENABLED 165 #if RPM_ENABLED == ENABLED 171 #if ADSB_ENABLED == ENABLED 175 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 189 #if ADVANCED_FAILSAFE == ENABLED 198 void setup()
override;
199 void loop()
override;
248 #if RPM_ENABLED == ENABLED 257 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 262 #if MODE_AUTO_ENABLED == ENABLED 283 #if OPTFLOW == ENABLED 304 #ifdef USERHOOK_VARIABLES 305 # include USERHOOK_VARIABLES 385 AP_BoardConfig_CAN BoardConfig_CAN;
416 #if FRAME_CONFIG == HELI_FRAME 417 #define MOTOR_CLASS AP_MotorsHeli 419 #define MOTOR_CLASS AP_MotorsMulticopter 449 #if FRSKY_TELEM_ENABLED == ENABLED 453 #if DEVO_TELEM_ENABLED == ENABLED 487 #if FRAME_CONFIG == HELI_FRAME 488 #define AC_AttitudeControl_t AC_AttitudeControl_Heli 490 #define AC_AttitudeControl_t AC_AttitudeControl_Multi 496 #if MODE_CIRCLE_ENABLED == ENABLED 515 #if CAMERA == ENABLED 526 #if AC_FENCE == ENABLED 530 #if AC_AVOID_ENABLED == ENABLED 531 # if BEACON_ENABLED == ENABLED 539 #if AC_RALLY == ENABLED 547 #if SPRAYER == ENABLED 552 #if PARACHUTE == ENABLED 560 #if AP_TERRAIN_AVAILABLE && AC_TERRAIN 565 #if PRECISION_LANDING == ENABLED 571 #if FRAME_CONFIG == HELI_FRAME 575 #if ADSB_ENABLED == ENABLED 588 #if VISUAL_ODOMETRY_ENABLED == ENABLED 597 #if FRAME_CONFIG == HELI_FRAME 605 uint8_t dynamic_flight : 1;
606 uint8_t init_targets_on_arming : 1;
607 uint8_t inverted_flight : 1;
609 heli_flags_t heli_flags;
611 int16_t hover_roll_trim_scalar_slew;
648 #define FAILSAFE_LAND_PRIORITY 1 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");
694 #if ADSB_ENABLED == ENABLED 717 void delay(uint32_t ms);
757 #if ADVANCED_FAILSAFE == ENABLED 758 void afs_fs_check(
void);
771 void send_rpm(mavlink_channel_t chan);
812 #if FRAME_CONFIG == HELI_FRAME 813 void Log_Write_Heli(
void);
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);
956 #if MODE_ACRO_ENABLED == ENABLED 957 #if FRAME_CONFIG == HELI_FRAME 964 #if MODE_AUTO_ENABLED == ENABLED 967 #if AUTOTUNE_ENABLED == ENABLED 970 #if MODE_BRAKE_ENABLED == ENABLED 973 #if MODE_CIRCLE_ENABLED == ENABLED 976 #if MODE_DRIFT_ENABLED == ENABLED 980 #if MODE_FOLLOW_ENABLED == ENABLED 983 #if MODE_GUIDED_ENABLED == ENABLED 987 #if MODE_LOITER_ENABLED == ENABLED 990 #if MODE_POSHOLD_ENABLED == ENABLED 993 #if MODE_RTL_ENABLED == ENABLED 996 #if FRAME_CONFIG == HELI_FRAME 1001 #if MODE_SPORT_ENABLED == ENABLED 1004 #if ADSB_ENABLED == ENABLED 1007 #if MODE_THROW_ENABLED == ENABLED 1010 #if MODE_GUIDED_NOGPS_ENABLED == ENABLED 1013 #if MODE_SMARTRTL_ENABLED == ENABLED 1016 #if !HAL_MINIMIZE_FEATURES && OPTFLOW == ENABLED
void esc_calibration_auto()
AP_DEVO_Telem devo_telemetry
AP_BoardConfig BoardConfig
void set_mode_SmartRTL_or_land_with_pause(mode_reason_t reason)
void init_aux_switch_function(int8_t ch_option, uint8_t ch_flag)
void update_land_detector()
struct Copter::@4 gndeffect_state
void read_barometer(void)
bool set_home(const Location &loc, bool lock)
void failsafe_radio_off_event()
struct Copter::@3 sensor_health
void esc_calibration_passthrough()
void avoidance_adsb_update(void)
LowPassFilterFloat rc_throttle_control_in_filter
void rotate_body_frame_to_NE(float &x, float &y)
bool rangefinder_alt_ok()
float auto_takeoff_no_nav_alt_cm
void set_auto_armed(bool b)
AC_AttitudeControl_t * attitude_control
void set_throttle_takeoff()
void send_extended_status1(mavlink_channel_t chan)
void Log_Write_Control_Tuning()
void update_flight_mode()
bool upgrading_frame_params
void read_control_switch()
uint32_t terrain_last_failure_ms
void userhook_SuperSlowLoop()
void set_home_to_current_location_inflight()
void set_land_complete_maybe(bool b)
LowPassFilterVector3f land_accel_ef_filter
bool ekf_over_threshold()
void takeoff_timer_start(float alt_cm)
void takeoff_get_climb_rates(float &pilot_climb_rate, float &takeoff_climb_rate)
float get_pilot_desired_throttle(int16_t throttle_control, float thr_mid=0.0f)
void convert_pid_parameters(void)
ModeStabilize mode_stabilize
AP_Avoidance_Copter avoidance_adsb
void radio_passthrough_to_motors()
void update_land_and_crash_detectors()
bool start_command(const AP_Mission::Mission_Command &cmd)
mode_reason_t prev_control_mode_reason
void update_throttle_hover()
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)
void init_rangefinder(void)
MAV_RESULT mavlink_compassmot(mavlink_channel_t chan)
void notify_flight_mode()
void set_mode_RTL_or_land_with_pause(mode_reason_t reason)
RC_Channel * channel_roll
void update_simple_mode(void)
struct _USB_OTG_GOTGCTL_TypeDef::@51 b
bool mavlink_motor_test_check(mavlink_channel_t chan, bool check_rc)
struct Copter::debounce aux_debounce[(CH_12 - CH_7)+1]
void twentyfive_hz_logging()
static const AP_Scheduler::Task scheduler_tasks[]
uint8_t motor_emergency_stop
uint8_t compass_init_location
void update_home_from_EKF()
void parachute_manual_release()
void gcs_data_stream_send(void)
void print_enabled(bool b)
void update_throttle_thr_mix()
uint32_t last_radio_update_ms
control_mode_t prev_control_mode
void set_mode_land_with_pause(mode_reason_t reason)
struct Copter::@0 rangefinder_state
void check_dynamic_flight(void)
void heli_update_landing_swash()
uint32_t control_sensors_health
AP_Frsky_Telem frsky_telemetry
uint8_t land_complete_maybe
void set_throttle_zero_flag(int16_t throttle_control)
void set_simple_mode(uint8_t b)
ModeSmartRTL mode_smartrtl
void Log_Write_GuidedTarget(uint8_t target_type, const Vector3f &pos_target, const Vector3f &vel_target)
ModeGuidedNoGPS mode_guided_nogps
uint8_t rc_override_enable
bool should_log(uint32_t mask)
AP_InertialNav_NavEKF inertial_nav
bool optflow_position_ok()
void Log_Write_Vehicle_Startup_Messages()
static const AP_Param::Info var_info[]
void Log_Write_Precland()
int8_t debounced_switch_position
AP_LandingGear landinggear
LowPassFilterFloat alt_cm_filt
uint8_t read_3pos_switch(uint8_t chan)
Mode * mode_from_mode_num(const uint8_t mode)
void auto_takeoff_attitude_run(float target_yaw_rate)
AP_SerialManager serial_manager
void update_visual_odom()
void failsafe_terrain_on_event()
void esc_calibration_notify()
void gcs_send_heartbeat(void)
uint8_t initialised_params
void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
int32_t super_simple_last_bearing
void failsafe_ekf_event()
bool init_arm_motors(bool arming_from_gcs)
void set_mode_SmartRTL_or_RTL(mode_reason_t reason)
void Log_Write_Performance()
int16_t get_throttle_mid(void)
mode_reason_t control_mode_reason
uint32_t last_edge_time_ms
void Log_Write_Error(uint8_t sub_system, uint8_t error_code)
uint32_t terrain_first_failure_ms
void reset_control_switch()
RC_Channel * channel_throttle
void init_capabilities(void)
void update_ground_effect_detector(void)
void ten_hz_logging_loop()
bool check_if_auxsw_mode_used(uint8_t auxsw_mode_check)
void allocate_motors(void)
bool check_duplicate_auxsw(void)
RC_Channel * channel_pitch
void load_parameters(void)
uint32_t esc_calibration_notify_update_ms
const char * get_frame_string()
#define AC_AttitudeControl_t
void lost_vehicle_check()
float pv_distance_to_home_cm(const Vector3f &destination)
ModeAvoidADSB mode_avoid_adsb
int8_t last_switch_position
void print_blanks(int16_t num)
bool start_command(const AP_Mission::Mission_Command &cmd)
takeoff_state_t takeoff_state
void update_using_interlock()
void Log_Write_Attitude()
void Log_Write_Event(uint8_t id)
void send_rpm(mavlink_channel_t chan)
uint8_t armed_with_switch
bool verify_command_callback(const AP_Mission::Mission_Command &cmd)
MAV_TYPE get_frame_mav_type()
float get_avoidance_adjusted_climbrate(float target_rate)
bool far_from_EKF_origin(const Location &loc)
void update_sensor_status_flags(void)
Location_Class current_loc
bool debounce_aux_switch(uint8_t chan, uint8_t ch_flag)
float ekfNavVelGainScaler
void send_fence_status(mavlink_channel_t chan)
static const AP_FWVersion fwver
void set_accel_throttle_I_from_pilot_throttle()
void run_nav_updates(void)
void failsafe_gcs_check()
void failsafe_radio_on_event()
float pv_alt_above_home(float alt_above_origin_cm)
void init_simple_bearing()
bool set_mode(control_mode_t mode, mode_reason_t reason)
void failsafe_ekf_off_event(void)
void set_failsafe_radio(bool b)
uint32_t last_heartbeat_ms
float pv_alt_above_origin(float alt_above_home_cm)
bool any_failsafe_triggered() const
static const struct LogStructure log_structure[]
void send_nav_controller_output(mavlink_channel_t chan)
void set_land_complete(bool b)
void failsafe_terrain_check()
ModeFlowHold mode_flowhold
void set_throttle_and_failsafe(uint16_t throttle_pwm)
DataFlash_Class DataFlash
void landinggear_update()
void handle_battery_failsafe(const char *type_str, const int8_t action)
bool do_user_takeoff(float takeoff_alt_cm, bool must_navigate)
static constexpr int8_t _failsafe_priorities[]
void fourhundred_hz_logging()
float get_pilot_desired_climb_rate(float throttle_control)
uint8_t rc_receiver_present
void update_super_simple_bearing(bool force_update)
uint32_t control_sensors_enabled
int32_t initial_armed_bearing
float target_rangefinder_alt
ModeAutoTune mode_autotune
uint8_t command_ack_counter
AP_ServoRelayEvents ServoRelayEvents
bool current_mode_has_user_takeoff(bool must_navigate)
uint8_t rc_override_active
void auto_takeoff_set_start_alt(void)
bool set_home_to_current_location(bool lock)
void failsafe_terrain_set_status(bool data_ok)
bool verify_command_callback(const AP_Mission::Mission_Command &cmd)
Vector3f pv_location_to_vector(const Location &loc)
void gcs_check_input(void)
void update_batt_compass(void)
void fence_send_mavlink_status(mavlink_channel_t chan)
void update_heli_control_dynamics(void)
struct Copter::@2 failsafe
AC_PosControl * pos_control
void esc_calibration_startup_check()
void init_disarm_motors()
void update_optical_flow(void)
void compass_accumulate(void)
float super_simple_sin_yaw
uint16_t get_pilot_speed_dn()
uint32_t control_sensors_present
float super_simple_cos_yaw
void exit_mode(Mode *&old_flightmode, Mode *&new_flightmode)
float get_non_takeoff_throttle()
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
void set_failsafe_gcs(bool b)
uint8_t motor_interlock_switch
void gcs_send_deferred(void)
void startup_INS_ground()
void heli_update_rotor_speed_targets()
void set_default_frame_class()
void accel_cal_update(void)
control_mode_t control_mode
void set_motor_emergency_stop(bool b)
bool has_failsafed(void) const
void compass_cal_update(void)
void enable_motor_output()
bool should_disarm_on_failsafe()
uint32_t visual_odom_last_update_ms
void set_system_time_from_GPS()
void Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, int16_t control_in, int16_t tune_low, int16_t tune_high)
AP_Vehicle::MultiCopter aparm
void default_dead_zones()
float get_pilot_desired_yaw_rate(int16_t stick_angle)
void failsafe_gcs_off_event(void)
uint8_t auto_trim_counter
struct Copter::@1 control_switch_state
void Log_Write_Data(uint8_t id, int32_t value)
void read_rangefinder(void)
void userhook_MediumLoop()
float get_surface_tracking_climb_rate(int16_t target_rate, float current_alt_target, float dt)
void send_pid_tuning(mavlink_channel_t chan)
#define FAILSAFE_LAND_PRIORITY
const struct AP_Param::GroupInfo * motors_var_info