APM:Copter
Classes | Public Member Functions | Public Attributes | Private Types | Private Member Functions | Private Attributes | Static Private Attributes | Friends | List of all members
Copter Struct Reference

#include <Copter.h>

Inheritance diagram for Copter:
[legend]
Collaboration diagram for Copter:
[legend]

Classes

union  ap_t
 
struct  debounce
 
class  Mode
 
class  ModeAcro
 
class  ModeAltHold
 
class  ModeAuto
 
class  ModeAutoTune
 
class  ModeAvoidADSB
 
class  ModeBrake
 
class  ModeCircle
 
class  ModeDrift
 
class  ModeFlip
 
class  ModeFlowHold
 
class  ModeFollow
 
class  ModeGuided
 
class  ModeGuidedNoGPS
 
class  ModeLand
 
class  ModeLoiter
 
class  ModePosHold
 
class  ModeRTL
 
class  ModeSmartRTL
 
class  ModeSport
 
class  ModeStabilize
 
class  ModeThrow
 
struct  takeoff_state_t
 

Public Member Functions

 Copter (void)
 
void setup () override
 
void loop () override
 
void mavlink_delay_cb ()
 
void failsafe_check ()
 

Public Attributes

 LOG_COMMON_STRUCTURES
 
bool enabled:1
 
bool alt_healthy:1
 
int16_t alt_cm
 
uint32_t last_healthy_ms
 
LowPassFilterFloat alt_cm_filt
 
int8_t glitch_count
 
int8_t debounced_switch_position
 
int8_t last_switch_position
 
uint32_t last_edge_time_ms
 
uint32_t last_heartbeat_ms
 
uint32_t terrain_first_failure_ms
 
uint32_t terrain_last_failure_ms
 
int8_t radio_counter
 
uint8_t rc_override_active: 1
 
uint8_t radio: 1
 
uint8_t gcs: 1
 
uint8_t ekf: 1
 
uint8_t terrain: 1
 
uint8_t adsb: 1
 
uint8_t baro: 1
 
uint8_t compass: 1
 
uint8_t primary_gps: 2
 
bool takeoff_expected
 
bool touchdown_expected
 
uint32_t takeoff_time_ms
 
float takeoff_alt_cm
 

Private Types

enum  Failsafe_Action {
  Failsafe_Action_None = 0, Failsafe_Action_Land = 1, Failsafe_Action_RTL = 2, Failsafe_Action_SmartRTL = 3,
  Failsafe_Action_SmartRTL_Land = 4, Failsafe_Action_Terminate = 5
}
 

Private Member Functions

bool start_command (const AP_Mission::Mission_Command &cmd)
 
bool verify_command_callback (const AP_Mission::Mission_Command &cmd)
 
void exit_mission ()
 
GCS_Coptergcs ()
 
bool any_failsafe_triggered () const
 
void set_auto_armed (bool b)
 
void set_simple_mode (uint8_t b)
 
void set_failsafe_radio (bool b)
 
void set_failsafe_gcs (bool b)
 
void update_using_interlock ()
 
void set_motor_emergency_stop (bool b)
 
void fast_loop ()
 
void rc_loop ()
 
void throttle_loop ()
 
void update_batt_compass (void)
 
void fourhundred_hz_logging ()
 
void ten_hz_logging_loop ()
 
void twentyfive_hz_logging ()
 
void three_hz_loop ()
 
void one_hz_loop ()
 
void update_GPS (void)
 
void init_simple_bearing ()
 
void update_simple_mode (void)
 
void update_super_simple_bearing (bool force_update)
 
void read_AHRS (void)
 
void update_altitude ()
 
float get_pilot_desired_yaw_rate (int16_t stick_angle)
 
void update_throttle_hover ()
 
void set_throttle_takeoff ()
 
float get_pilot_desired_throttle (int16_t throttle_control, float thr_mid=0.0f)
 
float get_pilot_desired_climb_rate (float throttle_control)
 
float get_non_takeoff_throttle ()
 
float get_surface_tracking_climb_rate (int16_t target_rate, float current_alt_target, float dt)
 
float get_avoidance_adjusted_climbrate (float target_rate)
 
void set_accel_throttle_I_from_pilot_throttle ()
 
void rotate_body_frame_to_NE (float &x, float &y)
 
uint16_t get_pilot_speed_dn ()
 
void avoidance_adsb_update (void)
 
void update_ground_effect_detector (void)
 
void init_capabilities (void)
 
void update_home_from_EKF ()
 
void set_home_to_current_location_inflight ()
 
bool set_home_to_current_location (bool lock)
 
bool set_home (const Location &loc, bool lock)
 
bool far_from_EKF_origin (const Location &loc)
 
void set_system_time_from_GPS ()
 
MAV_RESULT mavlink_compassmot (mavlink_channel_t chan)
 
void delay (uint32_t ms)
 
void crash_check ()
 
void parachute_check ()
 
void parachute_release ()
 
void parachute_manual_release ()
 
void ekf_check ()
 
bool ekf_over_threshold ()
 
void failsafe_ekf_event ()
 
void failsafe_ekf_off_event (void)
 
void check_ekf_reset ()
 
void esc_calibration_startup_check ()
 
void esc_calibration_passthrough ()
 
void esc_calibration_auto ()
 
void esc_calibration_notify ()
 
void failsafe_radio_on_event ()
 
void failsafe_radio_off_event ()
 
void handle_battery_failsafe (const char *type_str, const int8_t action)
 
void failsafe_gcs_check ()
 
void failsafe_gcs_off_event (void)
 
void failsafe_terrain_check ()
 
void failsafe_terrain_set_status (bool data_ok)
 
void failsafe_terrain_on_event ()
 
void gpsglitch_check ()
 
void set_mode_RTL_or_land_with_pause (mode_reason_t reason)
 
void set_mode_SmartRTL_or_RTL (mode_reason_t reason)
 
void set_mode_SmartRTL_or_land_with_pause (mode_reason_t reason)
 
bool should_disarm_on_failsafe ()
 
void update_events ()
 
void failsafe_enable ()
 
void failsafe_disable ()
 
void fence_check ()
 
void fence_send_mavlink_status (mavlink_channel_t chan)
 
void gcs_send_heartbeat (void)
 
void gcs_send_deferred (void)
 
void send_fence_status (mavlink_channel_t chan)
 
void send_extended_status1 (mavlink_channel_t chan)
 
void send_nav_controller_output (mavlink_channel_t chan)
 
void send_rpm (mavlink_channel_t chan)
 
void send_pid_tuning (mavlink_channel_t chan)
 
void gcs_data_stream_send (void)
 
void gcs_check_input (void)
 
void heli_init ()
 
void check_dynamic_flight (void)
 
void update_heli_control_dynamics (void)
 
void heli_update_landing_swash ()
 
void heli_update_rotor_speed_targets ()
 
void read_inertia ()
 
void update_land_and_crash_detectors ()
 
void update_land_detector ()
 
void set_land_complete (bool b)
 
void set_land_complete_maybe (bool b)
 
void update_throttle_thr_mix ()
 
void landinggear_update ()
 
void Log_Write_Optflow ()
 
void Log_Write_Control_Tuning ()
 
void Log_Write_Performance ()
 
void Log_Write_Attitude ()
 
void Log_Write_EKF_POS ()
 
void Log_Write_MotBatt ()
 
void Log_Write_Event (uint8_t id)
 
void Log_Write_Data (uint8_t id, int32_t value)
 
void Log_Write_Data (uint8_t id, uint32_t value)
 
void Log_Write_Data (uint8_t id, int16_t value)
 
void Log_Write_Data (uint8_t id, uint16_t value)
 
void Log_Write_Data (uint8_t id, float value)
 
void Log_Write_Error (uint8_t sub_system, uint8_t error_code)
 
void Log_Write_Parameter_Tuning (uint8_t param, float tuning_val, int16_t control_in, int16_t tune_low, int16_t tune_high)
 
void Log_Sensor_Health ()
 
void Log_Write_Precland ()
 
void Log_Write_GuidedTarget (uint8_t target_type, const Vector3f &pos_target, const Vector3f &vel_target)
 
void Log_Write_Vehicle_Startup_Messages ()
 
void log_init (void)
 
bool set_mode (control_mode_t mode, mode_reason_t reason)
 
void update_flight_mode ()
 
void notify_flight_mode ()
 
void set_mode_land_with_pause (mode_reason_t reason)
 
bool landing_with_GPS ()
 
void motor_test_output ()
 
bool mavlink_motor_test_check (mavlink_channel_t chan, bool check_rc)
 
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 motor_test_stop ()
 
void arm_motors_check ()
 
void auto_disarm_check ()
 
bool init_arm_motors (bool arming_from_gcs)
 
void init_disarm_motors ()
 
void motors_output ()
 
void lost_vehicle_check ()
 
void run_nav_updates (void)
 
int32_t home_bearing ()
 
uint32_t home_distance ()
 
void load_parameters (void)
 
void convert_pid_parameters (void)
 
Vector3f pv_location_to_vector (const Location &loc)
 
float pv_alt_above_origin (float alt_above_home_cm)
 
float pv_alt_above_home (float alt_above_origin_cm)
 
float pv_distance_to_home_cm (const Vector3f &destination)
 
void init_precland ()
 
void update_precland ()
 
void default_dead_zones ()
 
void init_rc_in ()
 
void init_rc_out ()
 
void enable_motor_output ()
 
void read_radio ()
 
void set_throttle_and_failsafe (uint16_t throttle_pwm)
 
void set_throttle_zero_flag (int16_t throttle_control)
 
void radio_passthrough_to_motors ()
 
int16_t get_throttle_mid (void)
 
void read_barometer (void)
 
void init_rangefinder (void)
 
void read_rangefinder (void)
 
bool rangefinder_alt_ok ()
 
void rpm_update ()
 
void init_compass ()
 
void compass_accumulate (void)
 
void init_optflow ()
 
void update_optical_flow (void)
 
void compass_cal_update (void)
 
void accel_cal_update (void)
 
void init_proximity ()
 
void update_proximity ()
 
void update_sensor_status_flags (void)
 
void init_visual_odom ()
 
void update_visual_odom ()
 
void winch_init ()
 
void winch_update ()
 
void report_compass ()
 
void print_blanks (int16_t num)
 
void print_divider (void)
 
void print_enabled (bool b)
 
void report_version ()
 
void read_control_switch ()
 
bool check_if_auxsw_mode_used (uint8_t auxsw_mode_check)
 
bool check_duplicate_auxsw (void)
 
void reset_control_switch ()
 
uint8_t read_3pos_switch (uint8_t chan)
 
void read_aux_switches ()
 
void init_aux_switches ()
 
void init_aux_switch_function (int8_t ch_option, uint8_t ch_flag)
 
void do_aux_switch_function (int8_t ch_function, uint8_t ch_flag)
 
bool debounce_aux_switch (uint8_t chan, uint8_t ch_flag)
 
void save_trim ()
 
void auto_trim ()
 
void init_ardupilot ()
 
void startup_INS_ground ()
 
bool position_ok ()
 
bool ekf_position_ok ()
 
bool optflow_position_ok ()
 
void update_auto_armed ()
 
void check_usb_mux (void)
 
bool should_log (uint32_t mask)
 
void set_default_frame_class ()
 
MAV_TYPE get_frame_mav_type ()
 
const char * get_frame_string ()
 
void allocate_motors (void)
 
bool current_mode_has_user_takeoff (bool must_navigate)
 
bool do_user_takeoff (float takeoff_alt_cm, bool must_navigate)
 
void takeoff_timer_start (float alt_cm)
 
void takeoff_stop ()
 
void takeoff_get_climb_rates (float &pilot_climb_rate, float &takeoff_climb_rate)
 
void auto_takeoff_set_start_alt (void)
 
void auto_takeoff_attitude_run (float target_yaw_rate)
 
void terrain_update ()
 
void terrain_logging ()
 
bool terrain_use ()
 
void tuning ()
 
void userhook_init ()
 
void userhook_FastLoop ()
 
void userhook_50Hz ()
 
void userhook_MediumLoop ()
 
void userhook_SlowLoop ()
 
void userhook_SuperSlowLoop ()
 
Modemode_from_mode_num (const uint8_t mode)
 
void exit_mode (Mode *&old_flightmode, Mode *&new_flightmode)
 

Private Attributes

AP_Vehicle::MultiCopter aparm
 
Parameters g
 
ParametersG2 g2
 
AP_Scheduler scheduler {FUNCTOR_BIND_MEMBER(&Copter::fast_loop, void)}
 
AP_Notify notify
 
uint8_t command_ack_counter
 
RC_Channelchannel_roll
 
RC_Channelchannel_pitch
 
RC_Channelchannel_throttle
 
RC_Channelchannel_yaw
 
DataFlash_Class DataFlash
 
AP_GPS gps
 
AP_Int8 * flight_modes
 
AP_Baro barometer
 
Compass compass
 
AP_InertialSensor ins
 
RangeFinder rangefinder {serial_manager, ROTATION_PITCH_270}
 
struct {
   bool   enabled:1
 
   bool   alt_healthy:1
 
   int16_t   alt_cm
 
   uint32_t   last_healthy_ms
 
   LowPassFilterFloat   alt_cm_filt
 
   int8_t   glitch_count
 
rangefinder_state = { false, false, 0, 0 }
 
AP_RPM rpm_sensor
 
NavEKF2 EKF2 {&ahrs, rangefinder}
 
NavEKF3 EKF3 {&ahrs, rangefinder}
 
AP_AHRS_NavEKF ahrs {EKF2, EKF3, AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF}
 
SITL::SITL sitl
 
AP_Mission mission
 
AP_Arming_Copter arming {ahrs, compass, battery, inertial_nav}
 
OpticalFlow optflow {ahrs}
 
float ekfGndSpdLimit
 
float ekfNavVelGainScaler
 
uint32_t ekfYawReset_ms
 
int8_t ekf_primary_core
 
AP_SerialManager serial_manager
 
GCS_Copter _gcs
 
ap_t ap
 
control_mode_t control_mode
 
mode_reason_t control_mode_reason = MODE_REASON_UNKNOWN
 
control_mode_t prev_control_mode
 
mode_reason_t prev_control_mode_reason = MODE_REASON_UNKNOWN
 
struct {
   int8_t   debounced_switch_position
 
   int8_t   last_switch_position
 
   uint32_t   last_edge_time_ms
 
control_switch_state
 
struct Copter::debounce aux_debounce [(CH_12 - CH_7)+1]
 
takeoff_state_t takeoff_state
 
float auto_takeoff_no_nav_alt_cm
 
RCMapper rcmap
 
float arming_altitude_m
 
AP_BoardConfig BoardConfig
 
struct {
   uint32_t   last_heartbeat_ms
 
   uint32_t   terrain_first_failure_ms
 
   uint32_t   terrain_last_failure_ms
 
   int8_t   radio_counter
 
   uint8_t   rc_override_active: 1
 
   uint8_t   radio: 1
 
   uint8_t   gcs: 1
 
   uint8_t   ekf: 1
 
   uint8_t   terrain: 1
 
   uint8_t   adsb: 1
 
failsafe
 
struct {
   uint8_t   baro: 1
 
   uint8_t   compass: 1
 
   uint8_t   primary_gps: 2
 
sensor_health
 
MOTOR_CLASSmotors
 
const struct AP_Param::GroupInfomotors_var_info
 
float scaleLongDown
 
int32_t _home_bearing
 
uint32_t _home_distance
 
float simple_cos_yaw
 
float simple_sin_yaw
 
int32_t super_simple_last_bearing
 
float super_simple_cos_yaw
 
float super_simple_sin_yaw
 
int32_t initial_armed_bearing
 
AP_BattMonitor battery
 
AP_Frsky_Telem frsky_telemetry {ahrs, battery, rangefinder}
 
AP_DEVO_Telem devo_telemetry {ahrs}
 
uint32_t control_sensors_present
 
uint32_t control_sensors_enabled
 
uint32_t control_sensors_health
 
int16_t climb_rate
 
float target_rangefinder_alt
 
int32_t baro_alt
 
float baro_climbrate
 
LowPassFilterVector3f land_accel_ef_filter
 
LowPassFilterFloat rc_throttle_control_in_filter
 
Location_Class current_loc
 
float G_Dt
 
AP_InertialNav_NavEKF inertial_nav
 
AC_AttitudeControl_tattitude_control
 
AC_PosControlpos_control
 
AC_WPNavwp_nav
 
AC_Loiterloiter_nav
 
AC_Circlecircle_nav
 
uint32_t arm_time_ms
 
uint8_t auto_trim_counter
 
AP_Relay relay
 
AP_ServoRelayEvents ServoRelayEvents {relay}
 
AP_Camera camera {&relay, MASK_LOG_CAMERA, current_loc, ahrs}
 
AP_Mount camera_mount {ahrs, current_loc}
 
AC_Fence fence {ahrs}
 
AC_Avoid avoid {ahrs, fence, g2.proximity, &g2.beacon}
 
AP_Rally_Copter rally {ahrs}
 
AP_RSSI rssi
 
AC_Sprayer sprayer
 
AP_Parachute parachute {relay}
 
AP_LandingGear landinggear
 
AC_PrecLand precland {ahrs}
 
AP_ADSB adsb
 
AP_Avoidance_Copter avoidance_adsb {ahrs, adsb}
 
uint32_t last_radio_update_ms
 
uint32_t esc_calibration_notify_update_ms
 
uint32_t visual_odom_last_update_ms
 
AP_Param param_loader
 
struct {
   bool   takeoff_expected
 
   bool   touchdown_expected
 
   uint32_t   takeoff_time_ms
 
   float   takeoff_alt_cm
 
gndeffect_state
 
bool upgrading_frame_params
 
Modeflightmode
 
ModeAcro mode_acro
 
ModeAltHold mode_althold
 
ModeAuto mode_auto
 
ModeAutoTune mode_autotune
 
ModeBrake mode_brake
 
ModeCircle mode_circle
 
ModeDrift mode_drift
 
ModeFlip mode_flip
 
ModeFollow mode_follow
 
ModeGuided mode_guided
 
ModeLand mode_land
 
ModeLoiter mode_loiter
 
ModePosHold mode_poshold
 
ModeRTL mode_rtl
 
ModeStabilize mode_stabilize
 
ModeSport mode_sport
 
ModeAvoidADSB mode_avoid_adsb
 
ModeThrow mode_throw
 
ModeGuidedNoGPS mode_guided_nogps
 
ModeSmartRTL mode_smartrtl
 
ModeFlowHold mode_flowhold
 

Static Private Attributes

static const AP_FWVersion fwver
 
static const AP_Scheduler::Task scheduler_tasks []
 
static const AP_Param::Info var_info []
 
static const struct LogStructure log_structure []
 
static constexpr int8_t _failsafe_priorities []
 

Friends

class GCS_MAVLINK_Copter
 
class GCS_Copter
 
class AP_Rally_Copter
 
class Parameters
 
class ParametersG2
 
class AP_Avoidance_Copter
 
class AP_Arming_Copter
 
class ToyMode
 

Detailed Description

Definition at line 180 of file Copter.h.

Member Enumeration Documentation

◆ Failsafe_Action

Enumerator
Failsafe_Action_None 
Failsafe_Action_Land 
Failsafe_Action_RTL 
Failsafe_Action_SmartRTL 
Failsafe_Action_SmartRTL_Land 
Failsafe_Action_Terminate 

Definition at line 629 of file Copter.h.

Constructor & Destructor Documentation

◆ Copter()

Copter::Copter ( void  )

Definition at line 26 of file Copter.cpp.

Member Function Documentation

◆ accel_cal_update()

void Copter::accel_cal_update ( void  )
private

Definition at line 193 of file sensors.cpp.

Here is the call graph for this function:

◆ allocate_motors()

void Copter::allocate_motors ( void  )
private

Definition at line 524 of file system.cpp.

Referenced by init_ardupilot().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ any_failsafe_triggered()

bool Copter::any_failsafe_triggered ( ) const
inlineprivate

Definition at line 404 of file Copter.h.

◆ arm_motors_check()

void Copter::arm_motors_check ( )
private

Definition at line 12 of file motors.cpp.

Here is the call graph for this function:

◆ auto_disarm_check()

void Copter::auto_disarm_check ( )
private

Definition at line 78 of file motors.cpp.

Here is the call graph for this function:

◆ auto_takeoff_attitude_run()

void Copter::auto_takeoff_attitude_run ( float  target_yaw_rate)
private

Definition at line 165 of file takeoff.cpp.

Here is the call graph for this function:

◆ auto_takeoff_set_start_alt()

void Copter::auto_takeoff_set_start_alt ( void  )
private

Definition at line 149 of file takeoff.cpp.

Here is the call graph for this function:

◆ auto_trim()

void Copter::auto_trim ( )
private

Definition at line 749 of file switches.cpp.

Here is the call graph for this function:

◆ avoidance_adsb_update()

void Copter::avoidance_adsb_update ( void  )
private

Definition at line 5 of file avoidance_adsb.cpp.

Here is the call graph for this function:

◆ check_duplicate_auxsw()

bool Copter::check_duplicate_auxsw ( void  )
private

Definition at line 88 of file switches.cpp.

◆ check_dynamic_flight()

void Copter::check_dynamic_flight ( void  )
private

◆ check_ekf_reset()

void Copter::check_ekf_reset ( )
private

Definition at line 180 of file ekf_check.cpp.

Referenced by fast_loop().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ check_if_auxsw_mode_used()

bool Copter::check_if_auxsw_mode_used ( uint8_t  auxsw_mode_check)
private

Definition at line 79 of file switches.cpp.

Referenced by lost_vehicle_check(), and update_using_interlock().

Here is the caller graph for this function:

◆ check_usb_mux()

void Copter::check_usb_mux ( void  )
private

Definition at line 421 of file system.cpp.

Referenced by init_ardupilot(), mavlink_delay_cb(), and one_hz_loop().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ compass_accumulate()

void Copter::compass_accumulate ( void  )
private

Definition at line 109 of file sensors.cpp.

Here is the call graph for this function:

◆ compass_cal_update()

void Copter::compass_cal_update ( void  )
private

Definition at line 165 of file sensors.cpp.

Here is the call graph for this function:

◆ convert_pid_parameters()

void Copter::convert_pid_parameters ( void  )
private

Definition at line 1088 of file Parameters.cpp.

Referenced by allocate_motors().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ crash_check()

void Copter::crash_check ( )
private

Definition at line 11 of file crash_check.cpp.

Referenced by update_land_and_crash_detectors().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ current_mode_has_user_takeoff()

bool Copter::current_mode_has_user_takeoff ( bool  must_navigate)
private

Definition at line 10 of file takeoff.cpp.

Referenced by do_user_takeoff().

Here is the caller graph for this function:

◆ debounce_aux_switch()

bool Copter::debounce_aux_switch ( uint8_t  chan,
uint8_t  ch_flag 
)
private

Definition at line 216 of file switches.cpp.

◆ default_dead_zones()

void Copter::default_dead_zones ( )
private

Definition at line 7 of file radio.cpp.

Referenced by init_rc_in().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ delay()

void Copter::delay ( uint32_t  ms)
private

Definition at line 3 of file compat.cpp.

Referenced by esc_calibration_auto(), esc_calibration_passthrough(), esc_calibration_startup_check(), and init_ardupilot().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ do_aux_switch_function()

void Copter::do_aux_switch_function ( int8_t  ch_function,
uint8_t  ch_flag 
)
private

Definition at line 239 of file switches.cpp.

Here is the call graph for this function:

◆ do_user_takeoff()

bool Copter::do_user_takeoff ( float  takeoff_alt_cm,
bool  must_navigate 
)
private

Definition at line 27 of file takeoff.cpp.

Here is the call graph for this function:

◆ ekf_check()

void Copter::ekf_check ( )
private

Definition at line 29 of file ekf_check.cpp.

Here is the call graph for this function:

◆ ekf_over_threshold()

bool Copter::ekf_over_threshold ( )
private

Definition at line 90 of file ekf_check.cpp.

Here is the call graph for this function:

◆ ekf_position_ok()

bool Copter::ekf_position_ok ( )
private

Definition at line 324 of file system.cpp.

Referenced by position_ok().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ enable_motor_output()

void Copter::enable_motor_output ( )
private

Definition at line 88 of file radio.cpp.

Referenced by init_ardupilot(), init_arm_motors(), mavlink_compassmot(), and mavlink_motor_test_start().

Here is the caller graph for this function:

◆ esc_calibration_auto()

void Copter::esc_calibration_auto ( )
private

Definition at line 132 of file esc_calibration.cpp.

Referenced by esc_calibration_startup_check().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ esc_calibration_notify()

void Copter::esc_calibration_notify ( )
private

Definition at line 199 of file esc_calibration.cpp.

Referenced by esc_calibration_auto(), and esc_calibration_passthrough().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ esc_calibration_passthrough()

void Copter::esc_calibration_passthrough ( )
private

Definition at line 87 of file esc_calibration.cpp.

Referenced by esc_calibration_startup_check().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ esc_calibration_startup_check()

void Copter::esc_calibration_startup_check ( )
private

Definition at line 19 of file esc_calibration.cpp.

Referenced by init_rc_out().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ exit_mission()

void Copter::exit_mission ( )
inlineprivate

Definition at line 274 of file Copter.h.

Here is the call graph for this function:

◆ exit_mode()

void Copter::exit_mode ( Copter::Mode *&  old_flightmode,
Copter::Mode *&  new_flightmode 
)
private

Definition at line 254 of file mode.cpp.

Referenced by set_mode().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ failsafe_check()

void Copter::failsafe_check ( )

Definition at line 35 of file failsafe.cpp.

Here is the call graph for this function:

◆ failsafe_disable()

void Copter::failsafe_disable ( )
private

Definition at line 27 of file failsafe.cpp.

Referenced by init_arm_motors(), and mavlink_compassmot().

Here is the caller graph for this function:

◆ failsafe_ekf_event()

void Copter::failsafe_ekf_event ( )
private

Definition at line 128 of file ekf_check.cpp.

◆ failsafe_ekf_off_event()

void Copter::failsafe_ekf_off_event ( void  )
private

Definition at line 167 of file ekf_check.cpp.

◆ failsafe_enable()

void Copter::failsafe_enable ( )
private

Definition at line 18 of file failsafe.cpp.

Referenced by init_ardupilot(), init_arm_motors(), and mavlink_compassmot().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ failsafe_gcs_check()

void Copter::failsafe_gcs_check ( )
private

Definition at line 87 of file events.cpp.

Referenced by three_hz_loop().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ failsafe_gcs_off_event()

void Copter::failsafe_gcs_off_event ( void  )
private

Definition at line 141 of file events.cpp.

Referenced by failsafe_gcs_check().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ failsafe_radio_off_event()

void Copter::failsafe_radio_off_event ( )
private

Definition at line 44 of file events.cpp.

Referenced by set_failsafe_radio().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ failsafe_radio_on_event()

void Copter::failsafe_radio_on_event ( )
private

Definition at line 7 of file events.cpp.

Referenced by set_failsafe_radio().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ failsafe_terrain_check()

void Copter::failsafe_terrain_check ( )
private

Definition at line 149 of file events.cpp.

Referenced by three_hz_loop().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ failsafe_terrain_on_event()

void Copter::failsafe_terrain_on_event ( )
private

Definition at line 188 of file events.cpp.

Referenced by failsafe_terrain_check().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ failsafe_terrain_set_status()

void Copter::failsafe_terrain_set_status ( bool  data_ok)
private

Definition at line 168 of file events.cpp.

Here is the call graph for this function:

◆ far_from_EKF_origin()

bool Copter::far_from_EKF_origin ( const Location loc)
private

Definition at line 116 of file commands.cpp.

Referenced by set_home().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ fast_loop()

void Copter::fast_loop ( )
private

Definition at line 219 of file ArduCopter.cpp.

Here is the call graph for this function:

◆ fence_check()

void Copter::fence_check ( )
private

Definition at line 9 of file fence.cpp.

Referenced by three_hz_loop().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ fence_send_mavlink_status()

void Copter::fence_send_mavlink_status ( mavlink_channel_t  chan)
private

Definition at line 54 of file fence.cpp.

Referenced by send_fence_status().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ fourhundred_hz_logging()

void Copter::fourhundred_hz_logging ( )
private

Definition at line 318 of file ArduCopter.cpp.

Here is the call graph for this function:

◆ gcs()

GCS_Copter& Copter::gcs ( )
inlineprivate

◆ gcs_check_input()

void Copter::gcs_check_input ( void  )
private

Definition at line 1628 of file GCS_Mavlink.cpp.

Referenced by mavlink_delay_cb(), and read_AHRS().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ gcs_data_stream_send()

void Copter::gcs_data_stream_send ( void  )
private

Definition at line 1620 of file GCS_Mavlink.cpp.

Referenced by mavlink_delay_cb().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ gcs_send_deferred()

void Copter::gcs_send_deferred ( void  )
private

Definition at line 10 of file GCS_Mavlink.cpp.

Referenced by mavlink_delay_cb().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ gcs_send_heartbeat()

void Copter::gcs_send_heartbeat ( void  )
private

Definition at line 5 of file GCS_Mavlink.cpp.

Referenced by mavlink_delay_cb().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_avoidance_adjusted_climbrate()

float Copter::get_avoidance_adjusted_climbrate ( float  target_rate)
private

Definition at line 223 of file Attitude.cpp.

Here is the call graph for this function:

◆ get_frame_mav_type()

MAV_TYPE Copter::get_frame_mav_type ( )
private

Definition at line 456 of file system.cpp.

Referenced by init_ardupilot().

Here is the caller graph for this function:

◆ get_frame_string()

const char * Copter::get_frame_string ( )
private

Definition at line 486 of file system.cpp.

Referenced by init_ardupilot().

Here is the caller graph for this function:

◆ get_non_takeoff_throttle()

float Copter::get_non_takeoff_throttle ( )
private

Definition at line 156 of file Attitude.cpp.

Referenced by update_land_detector().

Here is the caller graph for this function:

◆ get_pilot_desired_climb_rate()

float Copter::get_pilot_desired_climb_rate ( float  throttle_control)
private

Definition at line 114 of file Attitude.cpp.

Here is the call graph for this function:

◆ get_pilot_desired_throttle()

float Copter::get_pilot_desired_throttle ( int16_t  throttle_control,
float  thr_mid = 0.0f 
)
private

Definition at line 78 of file Attitude.cpp.

Here is the call graph for this function:

◆ get_pilot_desired_yaw_rate()

float Copter::get_pilot_desired_yaw_rate ( int16_t  stick_angle)
private

Definition at line 6 of file Attitude.cpp.

◆ get_pilot_speed_dn()

uint16_t Copter::get_pilot_speed_dn ( )
private

Definition at line 252 of file Attitude.cpp.

Referenced by get_pilot_desired_climb_rate().

Here is the caller graph for this function:

◆ get_surface_tracking_climb_rate()

float Copter::get_surface_tracking_climb_rate ( int16_t  target_rate,
float  current_alt_target,
float  dt 
)
private

Definition at line 163 of file Attitude.cpp.

Here is the call graph for this function:

◆ get_throttle_mid()

int16_t Copter::get_throttle_mid ( void  )
private

Definition at line 203 of file radio.cpp.

Referenced by auto_disarm_check(), get_pilot_desired_climb_rate(), and get_pilot_desired_throttle().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ gpsglitch_check()

void Copter::gpsglitch_check ( )
private

Definition at line 206 of file events.cpp.

Here is the call graph for this function:

◆ handle_battery_failsafe()

void Copter::handle_battery_failsafe ( const char *  type_str,
const int8_t  action 
)
private

Definition at line 51 of file events.cpp.

Here is the call graph for this function:

◆ heli_init()

void Copter::heli_init ( )
private

Referenced by init_ardupilot().

Here is the caller graph for this function:

◆ heli_update_landing_swash()

void Copter::heli_update_landing_swash ( )
private

Referenced by throttle_loop().

Here is the caller graph for this function:

◆ heli_update_rotor_speed_targets()

void Copter::heli_update_rotor_speed_targets ( )
private

Referenced by throttle_loop().

Here is the caller graph for this function:

◆ home_bearing()

int32_t Copter::home_bearing ( )
private

Definition at line 25 of file navigation.cpp.

Referenced by update_super_simple_bearing().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ home_distance()

uint32_t Copter::home_distance ( )
private

Definition at line 14 of file navigation.cpp.

Referenced by update_super_simple_bearing().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ init_ardupilot()

void Copter::init_ardupilot ( )
private

Definition at line 21 of file system.cpp.

Referenced by setup().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ init_arm_motors()

bool Copter::init_arm_motors ( bool  arming_from_gcs)
private

Definition at line 130 of file motors.cpp.

Referenced by arm_motors_check().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ init_aux_switch_function()

void Copter::init_aux_switch_function ( int8_t  ch_option,
uint8_t  ch_flag 
)
private

Definition at line 182 of file switches.cpp.

◆ init_aux_switches()

void Copter::init_aux_switches ( )
private

Definition at line 158 of file switches.cpp.

Referenced by init_ardupilot().

Here is the caller graph for this function:

◆ init_capabilities()

void Copter::init_capabilities ( void  )
private

Definition at line 3 of file capabilities.cpp.

Referenced by init_ardupilot().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ init_compass()

void Copter::init_compass ( )
private

Definition at line 90 of file sensors.cpp.

Referenced by init_ardupilot(), and mavlink_compassmot().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ init_disarm_motors()

void Copter::init_disarm_motors ( )
private

Definition at line 241 of file motors.cpp.

Referenced by arm_motors_check(), auto_disarm_check(), crash_check(), failsafe_gcs_check(), failsafe_radio_on_event(), failsafe_terrain_on_event(), fence_check(), handle_battery_failsafe(), parachute_release(), and set_land_complete().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ init_optflow()

void Copter::init_optflow ( )
private

Definition at line 128 of file sensors.cpp.

Referenced by init_ardupilot().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ init_precland()

void Copter::init_precland ( )
private

Definition at line 9 of file precision_landing.cpp.

Referenced by init_ardupilot().

Here is the caller graph for this function:

◆ init_proximity()

void Copter::init_proximity ( void  )
private

Definition at line 214 of file sensors.cpp.

Referenced by init_ardupilot().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ init_rangefinder()

void Copter::init_rangefinder ( void  )
private

Definition at line 14 of file sensors.cpp.

Referenced by init_ardupilot().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ init_rc_in()

void Copter::init_rc_in ( )
private

Definition at line 22 of file radio.cpp.

Referenced by init_ardupilot().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ init_rc_out()

void Copter::init_rc_out ( )
private

Definition at line 52 of file radio.cpp.

Referenced by init_ardupilot(), mavlink_compassmot(), and mavlink_motor_test_start().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ init_simple_bearing()

void Copter::init_simple_bearing ( )
private

Definition at line 485 of file ArduCopter.cpp.

Referenced by init_arm_motors().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ init_visual_odom()

void Copter::init_visual_odom ( )
private

Definition at line 425 of file sensors.cpp.

Referenced by init_ardupilot().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ landing_with_GPS()

bool Copter::landing_with_GPS ( )
private

Definition at line 162 of file mode_land.cpp.

Referenced by ten_hz_logging_loop().

Here is the caller graph for this function:

◆ landinggear_update()

void Copter::landinggear_update ( )
private

Definition at line 5 of file landing_gear.cpp.

Here is the call graph for this function:

◆ load_parameters()

void Copter::load_parameters ( void  )
private

Definition at line 1053 of file Parameters.cpp.

Referenced by init_ardupilot().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ log_init()

void Copter::log_init ( void  )
private

Definition at line 537 of file Log.cpp.

Referenced by init_ardupilot().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ Log_Sensor_Health()

void Copter::Log_Sensor_Health ( )
private

Definition at line 365 of file Log.cpp.

Referenced by fast_loop(), and log_init().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ Log_Write_Attitude()

void Copter::Log_Write_Attitude ( )
private

Definition at line 143 of file Log.cpp.

Referenced by fourhundred_hz_logging(), log_init(), and ten_hz_logging_loop().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ Log_Write_Control_Tuning()

void Copter::Log_Write_Control_Tuning ( )
private

Definition at line 113 of file Log.cpp.

Referenced by log_init(), and update_altitude().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ Log_Write_Data() [1/5]

void Copter::Log_Write_Data ( uint8_t  id,
int32_t  value 
)
private

Definition at line 264 of file Log.cpp.

Referenced by init_simple_bearing(), log_init(), and one_hz_loop().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ Log_Write_Data() [2/5]

void Copter::Log_Write_Data ( uint8_t  id,
uint32_t  value 
)
private

Definition at line 285 of file Log.cpp.

Here is the call graph for this function:

◆ Log_Write_Data() [3/5]

UNUSED_FUNCTION void Copter::Log_Write_Data ( uint8_t  id,
int16_t  value 
)
private

Definition at line 221 of file Log.cpp.

Here is the call graph for this function:

◆ Log_Write_Data() [4/5]

UNUSED_FUNCTION void Copter::Log_Write_Data ( uint8_t  id,
uint16_t  value 
)
private

Definition at line 243 of file Log.cpp.

Here is the call graph for this function:

◆ Log_Write_Data() [5/5]

UNUSED_FUNCTION void Copter::Log_Write_Data ( uint8_t  id,
float  value 
)
private

Definition at line 307 of file Log.cpp.

Here is the call graph for this function:

◆ Log_Write_EKF_POS()

void Copter::Log_Write_EKF_POS ( )
private

Definition at line 158 of file Log.cpp.

Referenced by log_init(), ten_hz_logging_loop(), and twentyfive_hz_logging().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ Log_Write_Error()

void Copter::Log_Write_Error ( uint8_t  sub_system,
uint8_t  error_code 
)
private

Definition at line 328 of file Log.cpp.

Referenced by crash_check(), failsafe_check(), failsafe_gcs_check(), failsafe_gcs_off_event(), failsafe_radio_off_event(), failsafe_radio_on_event(), failsafe_terrain_check(), failsafe_terrain_on_event(), fence_check(), gpsglitch_check(), handle_battery_failsafe(), init_compass(), log_init(), parachute_check(), parachute_manual_release(), read_radio(), and set_mode().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ Log_Write_Event()

void Copter::Log_Write_Event ( uint8_t  id)
private

Definition at line 200 of file Log.cpp.

Referenced by init_arm_motors(), init_disarm_motors(), landinggear_update(), log_init(), motors_output(), parachute_release(), set_auto_armed(), set_home(), set_land_complete(), set_land_complete_maybe(), set_motor_emergency_stop(), set_simple_mode(), and set_system_time_from_GPS().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ Log_Write_GuidedTarget()

void Copter::Log_Write_GuidedTarget ( uint8_t  target_type,
const Vector3f pos_target,
const Vector3f vel_target 
)
private

Definition at line 461 of file Log.cpp.

Referenced by log_init().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ Log_Write_MotBatt()

void Copter::Log_Write_MotBatt ( )
private

Definition at line 178 of file Log.cpp.

Referenced by log_init(), and ten_hz_logging_loop().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ Log_Write_Optflow()

void Copter::Log_Write_Optflow ( )
private

Definition at line 73 of file Log.cpp.

Referenced by log_init(), and update_optical_flow().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ Log_Write_Parameter_Tuning()

void Copter::Log_Write_Parameter_Tuning ( uint8_t  param,
float  tuning_val,
int16_t  control_in,
int16_t  tune_low,
int16_t  tune_high 
)
private

Definition at line 349 of file Log.cpp.

Referenced by log_init(), and tuning().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ Log_Write_Performance()

void Copter::Log_Write_Performance ( )
private

Referenced by log_init().

Here is the caller graph for this function:

◆ Log_Write_Precland()

void Copter::Log_Write_Precland ( )
private

Definition at line 420 of file Log.cpp.

Referenced by log_init(), and twentyfive_hz_logging().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ Log_Write_Vehicle_Startup_Messages()

void Copter::Log_Write_Vehicle_Startup_Messages ( )
private

Definition at line 524 of file Log.cpp.

Referenced by init_ardupilot(), and log_init().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ loop()

void Copter::loop ( )
overridevirtual

Implements AP_HAL::HAL::Callbacks.

Definition at line 211 of file ArduCopter.cpp.

Here is the call graph for this function:

◆ lost_vehicle_check()

void Copter::lost_vehicle_check ( )
private

Definition at line 340 of file motors.cpp.

Here is the call graph for this function:

◆ mavlink_compassmot()

MAV_RESULT Copter::mavlink_compassmot ( mavlink_channel_t  chan)
private

Definition at line 8 of file compassmot.cpp.

Here is the call graph for this function:

◆ mavlink_delay_cb()

void Copter::mavlink_delay_cb ( )

Definition at line 1588 of file GCS_Mavlink.cpp.

Here is the call graph for this function:

◆ mavlink_motor_test_check()

bool Copter::mavlink_motor_test_check ( mavlink_channel_t  chan,
bool  check_rc 
)
private

Definition at line 95 of file motor_test.cpp.

Referenced by mavlink_motor_test_start().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ mavlink_motor_test_start()

MAV_RESULT Copter::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 
)
private

Definition at line 129 of file motor_test.cpp.

Here is the call graph for this function:

◆ mode_from_mode_num()

Copter::Mode * Copter::mode_from_mode_num ( const uint8_t  mode)
private

Definition at line 36 of file mode.cpp.

Referenced by set_mode().

Here is the caller graph for this function:

◆ motor_test_output()

void Copter::motor_test_output ( )
private

Definition at line 21 of file motor_test.cpp.

Referenced by motors_output().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ motor_test_stop()

void Copter::motor_test_stop ( )
private

Definition at line 185 of file motor_test.cpp.

Referenced by motor_test_output().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ motors_output()

void Copter::motors_output ( )
private

Definition at line 292 of file motors.cpp.

Referenced by fast_loop().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ notify_flight_mode()

void Copter::notify_flight_mode ( )
private

Definition at line 312 of file mode.cpp.

Referenced by init_ardupilot(), and set_mode().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ one_hz_loop()

void Copter::one_hz_loop ( )
private

Definition at line 416 of file ArduCopter.cpp.

Here is the call graph for this function:

◆ optflow_position_ok()

bool Copter::optflow_position_ok ( )
private

Definition at line 344 of file system.cpp.

Referenced by position_ok(), and update_ground_effect_detector().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ parachute_check()

void Copter::parachute_check ( )
private

Definition at line 63 of file crash_check.cpp.

Referenced by update_land_and_crash_detectors().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ parachute_manual_release()

void Copter::parachute_manual_release ( )
private

Definition at line 154 of file crash_check.cpp.

Here is the call graph for this function:

◆ parachute_release()

void Copter::parachute_release ( )
private

Definition at line 136 of file crash_check.cpp.

Referenced by parachute_check(), and parachute_manual_release().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ position_ok()

bool Copter::position_ok ( )
private

Definition at line 312 of file system.cpp.

Referenced by home_bearing(), home_distance(), init_arm_motors(), and update_ground_effect_detector().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ print_blanks()

void Copter::print_blanks ( int16_t  num)
private

Definition at line 51 of file setup.cpp.

Referenced by report_compass(), and report_version().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ print_divider()

void Copter::print_divider ( void  )
private

Definition at line 59 of file setup.cpp.

Referenced by report_compass(), and report_version().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ print_enabled()

void Copter::print_enabled ( bool  b)
private

Definition at line 67 of file setup.cpp.

Referenced by report_compass().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ pv_alt_above_home()

float Copter::pv_alt_above_home ( float  alt_above_origin_cm)
private

Definition at line 26 of file position_vector.cpp.

Referenced by read_inertia().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ pv_alt_above_origin()

float Copter::pv_alt_above_origin ( float  alt_above_home_cm)
private

Definition at line 19 of file position_vector.cpp.

Referenced by pv_location_to_vector().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ pv_distance_to_home_cm()

float Copter::pv_distance_to_home_cm ( const Vector3f destination)
private

Definition at line 33 of file position_vector.cpp.

Here is the call graph for this function:

◆ pv_location_to_vector()

Vector3f Copter::pv_location_to_vector ( const Location loc)
private

Definition at line 11 of file position_vector.cpp.

Referenced by home_bearing(), home_distance(), and pv_distance_to_home_cm().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ radio_passthrough_to_motors()

void Copter::radio_passthrough_to_motors ( )
private

Definition at line 192 of file radio.cpp.

Referenced by read_radio().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ rangefinder_alt_ok()

bool Copter::rangefinder_alt_ok ( )
private

Definition at line 69 of file sensors.cpp.

Referenced by update_land_detector(), and update_precland().

Here is the caller graph for this function:

◆ rc_loop()

void Copter::rc_loop ( )
private

Definition at line 267 of file ArduCopter.cpp.

Here is the call graph for this function:

◆ read_3pos_switch()

uint8_t Copter::read_3pos_switch ( uint8_t  chan)
private

Definition at line 116 of file switches.cpp.

Here is the call graph for this function:

◆ read_AHRS()

void Copter::read_AHRS ( void  )
private

Definition at line 556 of file ArduCopter.cpp.

Referenced by fast_loop().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ read_aux_switches()

void Copter::read_aux_switches ( )
private

Definition at line 135 of file switches.cpp.

◆ read_barometer()

void Copter::read_barometer ( void  )
private

Definition at line 4 of file sensors.cpp.

Referenced by update_altitude().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ read_control_switch()

void Copter::read_control_switch ( )
private

Definition at line 16 of file switches.cpp.

Referenced by rc_loop().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ read_inertia()

void Copter::read_inertia ( )
private

Definition at line 4 of file inertia.cpp.

Referenced by fast_loop().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ read_radio()

void Copter::read_radio ( )
private

Definition at line 94 of file radio.cpp.

Referenced by esc_calibration_passthrough(), esc_calibration_startup_check(), mavlink_compassmot(), and rc_loop().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ read_rangefinder()

void Copter::read_rangefinder ( void  )
private

Definition at line 24 of file sensors.cpp.

Here is the call graph for this function:

◆ report_compass()

void Copter::report_compass ( )
private

Definition at line 4 of file setup.cpp.

Referenced by mavlink_compassmot().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ report_version()

void Copter::report_version ( )
private

Definition at line 76 of file setup.cpp.

Referenced by init_ardupilot().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ reset_control_switch()

void Copter::reset_control_switch ( )
private

Definition at line 109 of file switches.cpp.

Referenced by init_ardupilot().

Here is the caller graph for this function:

◆ rotate_body_frame_to_NE()

void Copter::rotate_body_frame_to_NE ( float &  x,
float &  y 
)
private

Definition at line 243 of file Attitude.cpp.

Here is the call graph for this function:

◆ rpm_update()

void Copter::rpm_update ( void  )
private

Definition at line 77 of file sensors.cpp.

Here is the call graph for this function:

◆ run_nav_updates()

void Copter::run_nav_updates ( void  )
private

Definition at line 6 of file navigation.cpp.

Here is the call graph for this function:

◆ save_trim()

void Copter::save_trim ( void  )
private

Definition at line 737 of file switches.cpp.

Here is the call graph for this function:

◆ send_extended_status1()

NOINLINE void Copter::send_extended_status1 ( mavlink_channel_t  chan)
private

Definition at line 133 of file GCS_Mavlink.cpp.

Here is the call graph for this function:

◆ send_fence_status()

NOINLINE void Copter::send_fence_status ( mavlink_channel_t  chan)
private

Definition at line 126 of file GCS_Mavlink.cpp.

Here is the call graph for this function:

◆ send_nav_controller_output()

void NOINLINE Copter::send_nav_controller_output ( mavlink_channel_t  chan)
private

Definition at line 159 of file GCS_Mavlink.cpp.

Here is the call graph for this function:

◆ send_pid_tuning()

void Copter::send_pid_tuning ( mavlink_channel_t  chan)
private

Definition at line 198 of file GCS_Mavlink.cpp.

Here is the call graph for this function:

◆ send_rpm()

void NOINLINE Copter::send_rpm ( mavlink_channel_t  chan)
private

Definition at line 182 of file GCS_Mavlink.cpp.

Here is the call graph for this function:

◆ set_accel_throttle_I_from_pilot_throttle()

void Copter::set_accel_throttle_I_from_pilot_throttle ( )
private

Definition at line 234 of file Attitude.cpp.

Referenced by exit_mode().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ set_auto_armed()

void Copter::set_auto_armed ( bool  b)
private

Definition at line 4 of file AP_State.cpp.

Referenced by do_user_takeoff(), and update_auto_armed().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ set_default_frame_class()

void Copter::set_default_frame_class ( )
private

Definition at line 446 of file system.cpp.

Referenced by init_ardupilot().

Here is the caller graph for this function:

◆ set_failsafe_gcs()

void Copter::set_failsafe_gcs ( bool  b)
private

Definition at line 74 of file AP_State.cpp.

Referenced by failsafe_gcs_check().

Here is the caller graph for this function:

◆ set_failsafe_radio()

void Copter::set_failsafe_radio ( bool  b)
private

Definition at line 47 of file AP_State.cpp.

Referenced by read_radio(), and set_throttle_and_failsafe().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ set_home()

bool Copter::set_home ( const Location loc,
bool  lock 
)
private

Definition at line 57 of file commands.cpp.

Referenced by set_home_to_current_location(), and set_home_to_current_location_inflight().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ set_home_to_current_location()

bool Copter::set_home_to_current_location ( bool  lock)
private

Definition at line 38 of file commands.cpp.

Referenced by init_arm_motors(), and update_home_from_EKF().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ set_home_to_current_location_inflight()

void Copter::set_home_to_current_location_inflight ( )
private

Definition at line 21 of file commands.cpp.

Referenced by update_home_from_EKF().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ set_land_complete()

void Copter::set_land_complete ( bool  b)
private

Definition at line 92 of file land_detector.cpp.

Referenced by init_ardupilot(), init_disarm_motors(), and update_land_detector().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ set_land_complete_maybe()

void Copter::set_land_complete_maybe ( bool  b)
private

Definition at line 124 of file land_detector.cpp.

Referenced by init_ardupilot(), init_disarm_motors(), and update_land_detector().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ set_mode()

bool Copter::set_mode ( control_mode_t  mode,
mode_reason_t  reason 
)
private

Definition at line 171 of file mode.cpp.

Referenced by fence_check(), set_mode_RTL_or_land_with_pause(), set_mode_SmartRTL_or_land_with_pause(), and set_mode_SmartRTL_or_RTL().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ set_mode_land_with_pause()

void Copter::set_mode_land_with_pause ( mode_reason_t  reason)
private

Definition at line 152 of file mode_land.cpp.

Referenced by failsafe_radio_on_event(), handle_battery_failsafe(), set_mode_RTL_or_land_with_pause(), and set_mode_SmartRTL_or_land_with_pause().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ set_mode_RTL_or_land_with_pause()

void Copter::set_mode_RTL_or_land_with_pause ( mode_reason_t  reason)
private

Definition at line 227 of file events.cpp.

Referenced by failsafe_gcs_check(), failsafe_radio_on_event(), failsafe_terrain_on_event(), handle_battery_failsafe(), and set_mode_SmartRTL_or_RTL().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ set_mode_SmartRTL_or_land_with_pause()

void Copter::set_mode_SmartRTL_or_land_with_pause ( mode_reason_t  reason)
private

Definition at line 241 of file events.cpp.

Referenced by failsafe_gcs_check(), failsafe_radio_on_event(), and handle_battery_failsafe().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ set_mode_SmartRTL_or_RTL()

void Copter::set_mode_SmartRTL_or_RTL ( mode_reason_t  reason)
private

Definition at line 254 of file events.cpp.

Referenced by failsafe_gcs_check(), failsafe_radio_on_event(), and handle_battery_failsafe().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ set_motor_emergency_stop()

void Copter::set_motor_emergency_stop ( bool  b)
private

Definition at line 93 of file AP_State.cpp.

Here is the call graph for this function:

◆ set_simple_mode()

void Copter::set_simple_mode ( uint8_t  b)
private

Set Simple mode

Parameters
[in]b0:false or disabled, 1:true or SIMPLE, 2:SUPERSIMPLE

Definition at line 22 of file AP_State.cpp.

Here is the call graph for this function:

◆ set_system_time_from_GPS()

void Copter::set_system_time_from_GPS ( )
private

Definition at line 129 of file commands.cpp.

Referenced by update_GPS().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ set_throttle_and_failsafe()

void Copter::set_throttle_and_failsafe ( uint16_t  throttle_pwm)
private

Definition at line 127 of file radio.cpp.

Referenced by read_radio().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ set_throttle_takeoff()

void Copter::set_throttle_takeoff ( )
private

Definition at line 68 of file Attitude.cpp.

Here is the call graph for this function:

◆ set_throttle_zero_flag()

void Copter::set_throttle_zero_flag ( int16_t  throttle_control)
private

Definition at line 173 of file radio.cpp.

Referenced by read_radio().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ setup()

void Copter::setup ( )
overridevirtual

Implements AP_HAL::HAL::Callbacks.

Definition at line 197 of file ArduCopter.cpp.

Here is the call graph for this function:

◆ should_disarm_on_failsafe()

bool Copter::should_disarm_on_failsafe ( )
private

Definition at line 266 of file events.cpp.

Referenced by failsafe_gcs_check(), failsafe_radio_on_event(), failsafe_terrain_on_event(), and handle_battery_failsafe().

Here is the caller graph for this function:

◆ should_log()

bool Copter::should_log ( uint32_t  mask)
private

Definition at line 435 of file system.cpp.

Referenced by fast_loop(), fourhundred_hz_logging(), init_simple_bearing(), one_hz_loop(), read_rangefinder(), rpm_update(), set_home(), ten_hz_logging_loop(), terrain_logging(), twentyfive_hz_logging(), update_altitude(), and update_batt_compass().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ start_command()

bool Copter::start_command ( const AP_Mission::Mission_Command cmd)
inlineprivate

Definition at line 268 of file Copter.h.

Here is the call graph for this function:

◆ startup_INS_ground()

void Copter::startup_INS_ground ( )
private

Definition at line 298 of file system.cpp.

Referenced by init_ardupilot().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ takeoff_get_climb_rates()

void Copter::takeoff_get_climb_rates ( float &  pilot_climb_rate,
float &  takeoff_climb_rate 
)
private

Definition at line 91 of file takeoff.cpp.

Here is the call graph for this function:

◆ takeoff_stop()

void Copter::takeoff_stop ( )
private

Definition at line 81 of file takeoff.cpp.

Referenced by takeoff_get_climb_rates().

Here is the caller graph for this function:

◆ takeoff_timer_start()

void Copter::takeoff_timer_start ( float  alt_cm)
private

Definition at line 63 of file takeoff.cpp.

Referenced by do_user_takeoff().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ ten_hz_logging_loop()

void Copter::ten_hz_logging_loop ( )
private

Definition at line 327 of file ArduCopter.cpp.

Here is the call graph for this function:

◆ terrain_logging()

void Copter::terrain_logging ( )
private

Definition at line 21 of file terrain.cpp.

Referenced by one_hz_loop().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ terrain_update()

void Copter::terrain_update ( )
private

Definition at line 4 of file terrain.cpp.

Here is the call graph for this function:

◆ terrain_use()

bool Copter::terrain_use ( )
private

Definition at line 31 of file terrain.cpp.

Referenced by update_precland().

Here is the caller graph for this function:

◆ three_hz_loop()

void Copter::three_hz_loop ( )
private

Definition at line 392 of file ArduCopter.cpp.

Here is the call graph for this function:

◆ throttle_loop()

void Copter::throttle_loop ( )
private

Definition at line 277 of file ArduCopter.cpp.

Here is the call graph for this function:

◆ tuning()

void Copter::tuning ( )
private

Definition at line 10 of file tuning.cpp.

Referenced by three_hz_loop().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ twentyfive_hz_logging()

void Copter::twentyfive_hz_logging ( )
private

Definition at line 367 of file ArduCopter.cpp.

Here is the call graph for this function:

◆ update_altitude()

void Copter::update_altitude ( )
private

Definition at line 570 of file ArduCopter.cpp.

Here is the call graph for this function:

◆ update_auto_armed()

void Copter::update_auto_armed ( )
private

Definition at line 383 of file system.cpp.

Referenced by throttle_loop().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ update_batt_compass()

void Copter::update_batt_compass ( void  )
private

Definition at line 299 of file ArduCopter.cpp.

Here is the call graph for this function:

◆ update_events()

void Copter::update_events ( void  )
private

Definition at line 286 of file events.cpp.

Referenced by three_hz_loop().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ update_flight_mode()

void Copter::update_flight_mode ( )
private

Definition at line 245 of file mode.cpp.

Referenced by fast_loop().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ update_GPS()

void Copter::update_GPS ( void  )
private

Definition at line 459 of file ArduCopter.cpp.

Here is the call graph for this function:

◆ update_ground_effect_detector()

void Copter::update_ground_effect_detector ( void  )
private

Definition at line 3 of file baro_ground_effect.cpp.

Referenced by throttle_loop().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ update_heli_control_dynamics()

void Copter::update_heli_control_dynamics ( void  )
private

Referenced by fast_loop().

Here is the caller graph for this function:

◆ update_home_from_EKF()

void Copter::update_home_from_EKF ( )
private

Definition at line 4 of file commands.cpp.

Referenced by fast_loop().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ update_land_and_crash_detectors()

void Copter::update_land_and_crash_detectors ( )
private

Definition at line 14 of file land_detector.cpp.

Referenced by fast_loop().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ update_land_detector()

void Copter::update_land_detector ( )
private

Definition at line 33 of file land_detector.cpp.

Referenced by update_land_and_crash_detectors().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ update_optical_flow()

void Copter::update_optical_flow ( void  )
private

Definition at line 138 of file sensors.cpp.

Here is the call graph for this function:

◆ update_precland()

void Copter::update_precland ( )
private

Definition at line 14 of file precision_landing.cpp.

Here is the call graph for this function:

◆ update_proximity()

void Copter::update_proximity ( )
private

◆ update_sensor_status_flags()

void Copter::update_sensor_status_flags ( void  )
private

Definition at line 226 of file sensors.cpp.

Referenced by one_hz_loop(), and send_extended_status1().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ update_simple_mode()

void Copter::update_simple_mode ( void  )
private

Definition at line 503 of file ArduCopter.cpp.

Here is the call graph for this function:

◆ update_super_simple_bearing()

void Copter::update_super_simple_bearing ( bool  force_update)
private

Definition at line 532 of file ArduCopter.cpp.

Referenced by init_arm_motors(), run_nav_updates(), and set_simple_mode().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ update_throttle_hover()

void Copter::update_throttle_hover ( )
private

Definition at line 38 of file Attitude.cpp.

Here is the call graph for this function:

◆ update_throttle_thr_mix()

void Copter::update_throttle_thr_mix ( )
private

Definition at line 139 of file land_detector.cpp.

Referenced by throttle_loop().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ update_using_interlock()

void Copter::update_using_interlock ( )
private

Definition at line 81 of file AP_State.cpp.

Referenced by init_ardupilot(), and one_hz_loop().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ update_visual_odom()

void Copter::update_visual_odom ( )
private

Definition at line 433 of file sensors.cpp.

Here is the call graph for this function:

◆ userhook_50Hz()

void Copter::userhook_50Hz ( )
private

◆ userhook_FastLoop()

void Copter::userhook_FastLoop ( )
private

◆ userhook_init()

void Copter::userhook_init ( )
private

◆ userhook_MediumLoop()

void Copter::userhook_MediumLoop ( )
private

◆ userhook_SlowLoop()

void Copter::userhook_SlowLoop ( )
private

◆ userhook_SuperSlowLoop()

void Copter::userhook_SuperSlowLoop ( )
private

◆ verify_command_callback()

bool Copter::verify_command_callback ( const AP_Mission::Mission_Command cmd)
inlineprivate

Definition at line 271 of file Copter.h.

Here is the call graph for this function:

◆ winch_init()

void Copter::winch_init ( )
private

Definition at line 456 of file sensors.cpp.

Referenced by init_ardupilot().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ winch_update()

void Copter::winch_update ( )
private

Definition at line 465 of file sensors.cpp.

Here is the call graph for this function:

Friends And Related Function Documentation

◆ AP_Arming_Copter

friend class AP_Arming_Copter
friend

Definition at line 192 of file Copter.h.

◆ AP_Avoidance_Copter

friend class AP_Avoidance_Copter
friend

Definition at line 187 of file Copter.h.

◆ AP_Rally_Copter

friend class AP_Rally_Copter
friend

Definition at line 184 of file Copter.h.

◆ GCS_Copter

friend class GCS_Copter
friend

Definition at line 183 of file Copter.h.

◆ GCS_MAVLINK_Copter

friend class GCS_MAVLINK_Copter
friend

Definition at line 182 of file Copter.h.

◆ Parameters

friend class Parameters
friend

Definition at line 185 of file Copter.h.

◆ ParametersG2

friend class ParametersG2
friend

Definition at line 186 of file Copter.h.

◆ ToyMode

friend class ToyMode
friend

Definition at line 193 of file Copter.h.

Member Data Documentation

◆ _failsafe_priorities

constexpr int8_t Copter::_failsafe_priorities
staticprivate

◆ _gcs

GCS_Copter Copter::_gcs
private

Definition at line 300 of file Copter.h.

Referenced by gcs().

◆ _home_bearing

int32_t Copter::_home_bearing
private

Definition at line 429 of file Copter.h.

Referenced by home_bearing().

◆ _home_distance

uint32_t Copter::_home_distance
private

Definition at line 430 of file Copter.h.

Referenced by home_distance().

◆ adsb [1/2]

uint8_t Copter::adsb

Definition at line 401 of file Copter.h.

Referenced by avoidance_adsb_update(), one_hz_loop(), and set_mode().

◆ adsb [2/2]

AP_ADSB Copter::adsb
private

Definition at line 576 of file Copter.h.

◆ ahrs

◆ alt_cm

int16_t Copter::alt_cm

Definition at line 242 of file Copter.h.

Referenced by takeoff_timer_start().

◆ alt_cm_filt

LowPassFilterFloat Copter::alt_cm_filt

Definition at line 244 of file Copter.h.

◆ alt_healthy

bool Copter::alt_healthy

Definition at line 241 of file Copter.h.

◆ ap

ap_t Copter::ap
private

Definition at line 341 of file Copter.h.

◆ aparm

AP_Vehicle::MultiCopter Copter::aparm
private

◆ arm_time_ms

uint32_t Copter::arm_time_ms
private

Definition at line 503 of file Copter.h.

Referenced by init_arm_motors(), and motors_output().

◆ arming

AP_Arming_Copter Copter::arming {ahrs, compass, battery, inertial_nav}
private

◆ arming_altitude_m

float Copter::arming_altitude_m
private

Definition at line 378 of file Copter.h.

Referenced by init_arm_motors().

◆ attitude_control

AC_AttitudeControl_t* Copter::attitude_control
private

◆ auto_takeoff_no_nav_alt_cm

float Copter::auto_takeoff_no_nav_alt_cm
private

Definition at line 373 of file Copter.h.

Referenced by auto_takeoff_attitude_run(), and auto_takeoff_set_start_alt().

◆ auto_trim_counter

uint8_t Copter::auto_trim_counter
private

Definition at line 506 of file Copter.h.

Referenced by arm_motors_check().

◆ aux_debounce

struct Copter::debounce Copter::aux_debounce[(CH_12 - CH_7)+1]
private

◆ avoid

AC_Avoid Copter::avoid {ahrs, fence, g2.proximity, &g2.beacon}
private

Definition at line 532 of file Copter.h.

Referenced by get_avoidance_adjusted_climbrate(), and init_ardupilot().

◆ avoidance_adsb

AP_Avoidance_Copter Copter::avoidance_adsb {ahrs, adsb}
private

Definition at line 579 of file Copter.h.

Referenced by avoidance_adsb_update().

◆ baro

uint8_t Copter::baro

Definition at line 410 of file Copter.h.

◆ baro_alt

int32_t Copter::baro_alt
private

Definition at line 466 of file Copter.h.

Referenced by parachute_check(), and read_barometer().

◆ baro_climbrate

float Copter::baro_climbrate
private

Definition at line 467 of file Copter.h.

Referenced by read_barometer().

◆ barometer

AP_Baro Copter::barometer
private

Definition at line 234 of file Copter.h.

Referenced by init_ardupilot(), read_barometer(), and update_sensor_status_flags().

◆ battery

AP_BattMonitor Copter::battery
private

◆ BoardConfig

AP_BoardConfig Copter::BoardConfig
private

◆ camera

AP_Camera Copter::camera {&relay, MASK_LOG_CAMERA, current_loc, ahrs}
private

Definition at line 516 of file Copter.h.

Referenced by set_mode(), and update_GPS().

◆ camera_mount

AP_Mount Copter::camera_mount {ahrs, current_loc}
private

Definition at line 522 of file Copter.h.

Referenced by exit_mode(), fast_loop(), and init_ardupilot().

◆ channel_pitch

RC_Channel* Copter::channel_pitch
private

◆ channel_roll

RC_Channel* Copter::channel_roll
private

◆ channel_throttle

RC_Channel* Copter::channel_throttle
private

◆ channel_yaw

RC_Channel* Copter::channel_yaw
private

◆ circle_nav

AC_Circle* Copter::circle_nav
private

Definition at line 497 of file Copter.h.

Referenced by allocate_motors(), and tuning().

◆ climb_rate

int16_t Copter::climb_rate
private

Definition at line 464 of file Copter.h.

Referenced by read_inertia(), and update_throttle_hover().

◆ command_ack_counter

uint8_t Copter::command_ack_counter
private

Definition at line 218 of file Copter.h.

Referenced by mavlink_compassmot().

◆ compass [1/2]

Compass Copter::compass
private

◆ compass [2/2]

uint8_t Copter::compass

Definition at line 411 of file Copter.h.

◆ control_mode

control_mode_t Copter::control_mode
private

◆ control_mode_reason

mode_reason_t Copter::control_mode_reason = MODE_REASON_UNKNOWN
private

Definition at line 346 of file Copter.h.

Referenced by init_arm_motors(), and set_mode().

◆ control_sensors_enabled

uint32_t Copter::control_sensors_enabled
private

Definition at line 459 of file Copter.h.

Referenced by send_extended_status1(), and update_sensor_status_flags().

◆ control_sensors_health

uint32_t Copter::control_sensors_health
private

Definition at line 460 of file Copter.h.

Referenced by send_extended_status1(), and update_sensor_status_flags().

◆ control_sensors_present

uint32_t Copter::control_sensors_present
private

Definition at line 458 of file Copter.h.

Referenced by send_extended_status1(), and update_sensor_status_flags().

◆ control_switch_state

struct { ... } Copter::control_switch_state

◆ current_loc

Location_Class Copter::current_loc
private

◆ DataFlash

DataFlash_Class Copter::DataFlash
private

◆ debounced_switch_position

int8_t Copter::debounced_switch_position

Definition at line 353 of file Copter.h.

◆ devo_telemetry

AP_DEVO_Telem Copter::devo_telemetry {ahrs}
private

Definition at line 454 of file Copter.h.

Referenced by init_ardupilot(), and set_mode().

◆ ekf

uint8_t Copter::ekf

Definition at line 399 of file Copter.h.

◆ EKF2

NavEKF2 Copter::EKF2 {&ahrs, rangefinder}
private

Definition at line 253 of file Copter.h.

◆ EKF3

NavEKF3 Copter::EKF3 {&ahrs, rangefinder}
private

Definition at line 254 of file Copter.h.

◆ ekf_primary_core

int8_t Copter::ekf_primary_core
private

Definition at line 295 of file Copter.h.

◆ ekfGndSpdLimit

float Copter::ekfGndSpdLimit
private

Definition at line 288 of file Copter.h.

◆ ekfNavVelGainScaler

float Copter::ekfNavVelGainScaler
private

Definition at line 291 of file Copter.h.

◆ ekfYawReset_ms

uint32_t Copter::ekfYawReset_ms
private

Definition at line 294 of file Copter.h.

◆ enabled

bool Copter::enabled

Definition at line 240 of file Copter.h.

Referenced by optflow_position_ok().

◆ esc_calibration_notify_update_ms

uint32_t Copter::esc_calibration_notify_update_ms
private

Definition at line 586 of file Copter.h.

Referenced by esc_calibration_notify().

◆ failsafe

struct { ... } Copter::failsafe

◆ fence

AC_Fence Copter::fence {ahrs}
private

Definition at line 527 of file Copter.h.

Referenced by failsafe_check(), fence_check(), fence_send_mavlink_status(), and set_mode().

◆ flight_modes

AP_Int8* Copter::flight_modes
private

Definition at line 232 of file Copter.h.

◆ flightmode

Mode* Copter::flightmode
private

◆ frsky_telemetry

AP_Frsky_Telem Copter::frsky_telemetry {ahrs, battery, rangefinder}
private

Definition at line 451 of file Copter.h.

Referenced by init_ardupilot(), set_mode(), and update_sensor_status_flags().

◆ fwver

const AP_FWVersion Copter::fwver
staticprivate
Initial value:
{
.major = FW_MAJOR,
.minor = FW_MINOR,
.patch = FW_PATCH,
.fw_type = FW_TYPE,
.fw_string = THISFIRMWARE,
}

Definition at line 202 of file Copter.h.

Referenced by init_ardupilot().

◆ g

Parameters Copter::g
private

◆ g2

ParametersG2 Copter::g2
private

◆ G_Dt

float Copter::G_Dt
private

Definition at line 480 of file Copter.h.

Referenced by get_avoidance_adjusted_climbrate(), init_ardupilot(), loop(), and read_inertia().

◆ gcs

uint8_t Copter::gcs

Definition at line 398 of file Copter.h.

◆ glitch_count

int8_t Copter::glitch_count

Definition at line 245 of file Copter.h.

◆ gndeffect_state

struct { ... } Copter::gndeffect_state

◆ gps

AP_GPS Copter::gps
private

◆ inertial_nav

AP_InertialNav_NavEKF Copter::inertial_nav
private

◆ initial_armed_bearing

int32_t Copter::initial_armed_bearing
private

Definition at line 442 of file Copter.h.

Referenced by init_arm_motors().

◆ ins

AP_InertialSensor Copter::ins
private

◆ land_accel_ef_filter

LowPassFilterVector3f Copter::land_accel_ef_filter
private

Definition at line 468 of file Copter.h.

Referenced by crash_check(), update_land_and_crash_detectors(), and update_land_detector().

◆ landinggear

AP_LandingGear Copter::landinggear
private

Definition at line 557 of file Copter.h.

Referenced by init_ardupilot(), landinggear_update(), and parachute_release().

◆ last_edge_time_ms

uint32_t Copter::last_edge_time_ms

Definition at line 355 of file Copter.h.

◆ last_healthy_ms

uint32_t Copter::last_healthy_ms

Definition at line 243 of file Copter.h.

◆ last_heartbeat_ms

uint32_t Copter::last_heartbeat_ms

Definition at line 390 of file Copter.h.

◆ last_radio_update_ms

uint32_t Copter::last_radio_update_ms
private

Definition at line 583 of file Copter.h.

Referenced by esc_calibration_startup_check(), failsafe_check(), and read_radio().

◆ last_switch_position

int8_t Copter::last_switch_position

Definition at line 354 of file Copter.h.

◆ LOG_COMMON_STRUCTURES

Copter::LOG_COMMON_STRUCTURES

Definition at line 481 of file Log.cpp.

◆ log_structure

const struct LogStructure Copter::log_structure[]
staticprivate

Definition at line 627 of file Copter.h.

◆ loiter_nav

AC_Loiter* Copter::loiter_nav
private

Definition at line 495 of file Copter.h.

Referenced by allocate_motors(), and init_ardupilot().

◆ mission

AP_Mission Copter::mission
private

◆ mode_acro

ModeAcro Copter::mode_acro
private

Definition at line 960 of file Copter.h.

Referenced by exit_mode(), and mode_from_mode_num().

◆ mode_althold

ModeAltHold Copter::mode_althold
private

Definition at line 963 of file Copter.h.

Referenced by mode_from_mode_num().

◆ mode_auto

ModeAuto Copter::mode_auto
private

◆ mode_autotune

ModeAutoTune Copter::mode_autotune
private

Definition at line 968 of file Copter.h.

Referenced by exit_mode(), init_disarm_motors(), and mode_from_mode_num().

◆ mode_avoid_adsb

ModeAvoidADSB Copter::mode_avoid_adsb
private

Definition at line 1005 of file Copter.h.

Referenced by mode_from_mode_num().

◆ mode_brake

ModeBrake Copter::mode_brake
private

Definition at line 971 of file Copter.h.

Referenced by mode_from_mode_num().

◆ mode_circle

ModeCircle Copter::mode_circle
private

Definition at line 974 of file Copter.h.

Referenced by mode_from_mode_num().

◆ mode_drift

ModeDrift Copter::mode_drift
private

Definition at line 977 of file Copter.h.

Referenced by mode_from_mode_num().

◆ mode_flip

ModeFlip Copter::mode_flip
private

Definition at line 979 of file Copter.h.

Referenced by mode_from_mode_num().

◆ mode_flowhold

ModeFlowHold Copter::mode_flowhold
private

Definition at line 1017 of file Copter.h.

◆ mode_follow

ModeFollow Copter::mode_follow
private

Definition at line 981 of file Copter.h.

Referenced by mode_from_mode_num().

◆ mode_guided

ModeGuided Copter::mode_guided
private

Definition at line 984 of file Copter.h.

Referenced by do_user_takeoff(), and mode_from_mode_num().

◆ mode_guided_nogps

ModeGuidedNoGPS Copter::mode_guided_nogps
private

Definition at line 1011 of file Copter.h.

Referenced by mode_from_mode_num().

◆ mode_land

ModeLand Copter::mode_land
private

Definition at line 986 of file Copter.h.

Referenced by mode_from_mode_num().

◆ mode_loiter

ModeLoiter Copter::mode_loiter
private

Definition at line 988 of file Copter.h.

Referenced by mode_from_mode_num().

◆ mode_poshold

ModePosHold Copter::mode_poshold
private

Definition at line 991 of file Copter.h.

Referenced by mode_from_mode_num().

◆ mode_rtl

ModeRTL Copter::mode_rtl
private

Definition at line 994 of file Copter.h.

Referenced by failsafe_terrain_on_event(), and mode_from_mode_num().

◆ mode_smartrtl

ModeSmartRTL Copter::mode_smartrtl
private

Definition at line 1014 of file Copter.h.

Referenced by exit_mode(), and mode_from_mode_num().

◆ mode_sport

ModeSport Copter::mode_sport
private

Definition at line 1002 of file Copter.h.

Referenced by mode_from_mode_num().

◆ mode_stabilize

ModeStabilize Copter::mode_stabilize
private

Definition at line 999 of file Copter.h.

Referenced by exit_mode(), and mode_from_mode_num().

◆ mode_throw

ModeThrow Copter::mode_throw
private

Definition at line 1008 of file Copter.h.

Referenced by mode_from_mode_num().

◆ motors

MOTOR_CLASS* Copter::motors
private

◆ motors_var_info

const struct AP_Param::GroupInfo* Copter::motors_var_info
private

Definition at line 423 of file Copter.h.

Referenced by allocate_motors().

◆ notify

AP_Notify Copter::notify
private

◆ optflow

OpticalFlow Copter::optflow {ahrs}
private

◆ parachute

AP_Parachute Copter::parachute {relay}
private

Definition at line 553 of file Copter.h.

Referenced by parachute_check(), parachute_manual_release(), and parachute_release().

◆ param_loader

AP_Param Copter::param_loader
private

Definition at line 595 of file Copter.h.

◆ pos_control

AC_PosControl* Copter::pos_control
private

◆ precland

AC_PrecLand Copter::precland {ahrs}
private

◆ prev_control_mode

control_mode_t Copter::prev_control_mode
private

◆ prev_control_mode_reason

mode_reason_t Copter::prev_control_mode_reason = MODE_REASON_UNKNOWN
private

Definition at line 349 of file Copter.h.

◆ primary_gps

uint8_t Copter::primary_gps

Definition at line 412 of file Copter.h.

◆ radio

uint8_t Copter::radio

Definition at line 397 of file Copter.h.

◆ radio_counter

int8_t Copter::radio_counter

Definition at line 394 of file Copter.h.

◆ rally

AP_Rally_Copter Copter::rally {ahrs}
private

Definition at line 540 of file Copter.h.

Referenced by Copter::ModeBrake::is_autopilot().

◆ rangefinder

RangeFinder Copter::rangefinder {serial_manager, ROTATION_PITCH_270}
private

◆ rangefinder_state

struct { ... } Copter::rangefinder_state

◆ rc_override_active

uint8_t Copter::rc_override_active

Definition at line 396 of file Copter.h.

◆ rc_throttle_control_in_filter

LowPassFilterFloat Copter::rc_throttle_control_in_filter
private

Definition at line 471 of file Copter.h.

Referenced by Copter::Mode::land_run_horizontal_control(), and read_radio().

◆ rcmap

RCMapper Copter::rcmap
private

Definition at line 375 of file Copter.h.

Referenced by init_rc_in().

◆ relay

AP_Relay Copter::relay
private

Definition at line 509 of file Copter.h.

Referenced by init_ardupilot().

◆ rpm_sensor

AP_RPM Copter::rpm_sensor
private

Definition at line 249 of file Copter.h.

Referenced by init_ardupilot(), rpm_update(), and send_rpm().

◆ rssi

AP_RSSI Copter::rssi
private

Definition at line 544 of file Copter.h.

Referenced by init_ardupilot(), and ten_hz_logging_loop().

◆ scaleLongDown

float Copter::scaleLongDown
private

Definition at line 427 of file Copter.h.

Referenced by pv_location_to_vector(), and set_home().

◆ scheduler

AP_Scheduler Copter::scheduler {FUNCTOR_BIND_MEMBER(&Copter::fast_loop, void)}
private

◆ scheduler_tasks

const AP_Scheduler::Task Copter::scheduler_tasks
staticprivate

Definition at line 625 of file Copter.h.

Referenced by setup().

◆ sensor_health

struct { ... } Copter::sensor_health

Referenced by Copter().

◆ serial_manager

AP_SerialManager Copter::serial_manager
private

Definition at line 297 of file Copter.h.

Referenced by init_ardupilot().

◆ ServoRelayEvents

AP_ServoRelayEvents Copter::ServoRelayEvents {relay}
private

Definition at line 512 of file Copter.h.

Referenced by init_ardupilot(), and update_events().

◆ simple_cos_yaw

float Copter::simple_cos_yaw
private

Definition at line 435 of file Copter.h.

Referenced by init_simple_bearing(), and update_simple_mode().

◆ simple_sin_yaw

float Copter::simple_sin_yaw
private

Definition at line 436 of file Copter.h.

Referenced by init_simple_bearing(), and update_simple_mode().

◆ sitl

SITL::SITL Copter::sitl
private

Definition at line 258 of file Copter.h.

◆ sprayer

AC_Sprayer Copter::sprayer
private

Definition at line 548 of file Copter.h.

Referenced by init_arm_motors(), and three_hz_loop().

◆ super_simple_cos_yaw

float Copter::super_simple_cos_yaw
private

Definition at line 438 of file Copter.h.

Referenced by init_simple_bearing(), update_simple_mode(), and update_super_simple_bearing().

◆ super_simple_last_bearing

int32_t Copter::super_simple_last_bearing
private

Definition at line 437 of file Copter.h.

Referenced by init_simple_bearing(), and update_super_simple_bearing().

◆ super_simple_sin_yaw

float Copter::super_simple_sin_yaw
private

Definition at line 439 of file Copter.h.

Referenced by init_simple_bearing(), update_simple_mode(), and update_super_simple_bearing().

◆ takeoff_alt_cm

float Copter::takeoff_alt_cm

Definition at line 619 of file Copter.h.

◆ takeoff_expected

bool Copter::takeoff_expected

Definition at line 616 of file Copter.h.

◆ takeoff_state

takeoff_state_t Copter::takeoff_state
private

Definition at line 370 of file Copter.h.

Referenced by takeoff_get_climb_rates(), takeoff_stop(), and takeoff_timer_start().

◆ takeoff_time_ms

uint32_t Copter::takeoff_time_ms

Definition at line 618 of file Copter.h.

◆ target_rangefinder_alt

float Copter::target_rangefinder_alt
private

Definition at line 465 of file Copter.h.

Referenced by get_surface_tracking_climb_rate().

◆ terrain

uint8_t Copter::terrain

◆ terrain_first_failure_ms

uint32_t Copter::terrain_first_failure_ms

Definition at line 391 of file Copter.h.

◆ terrain_last_failure_ms

uint32_t Copter::terrain_last_failure_ms

Definition at line 392 of file Copter.h.

◆ touchdown_expected

bool Copter::touchdown_expected

Definition at line 617 of file Copter.h.

◆ upgrading_frame_params

bool Copter::upgrading_frame_params
private

Definition at line 623 of file Copter.h.

Referenced by allocate_motors().

◆ var_info

const AP_Param::Info Copter::var_info
staticprivate

Definition at line 626 of file Copter.h.

◆ visual_odom_last_update_ms

uint32_t Copter::visual_odom_last_update_ms
private

Definition at line 590 of file Copter.h.

Referenced by update_visual_odom().

◆ wp_nav

AC_WPNav* Copter::wp_nav
private

The documentation for this struct was generated from the following files: