#pragma once
#include <cmath>
#include <stdio.h>
#include <stdarg.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Common/AP_Common.h>
#include <AP_Common/Location.h>
#include <AP_Param/AP_Param.h>
#include <StorageManager/StorageManager.h>
#include <AP_Logger/AP_Logger.h>
#include <AP_Math/AP_Math.h>
#include <AP_AccelCal/AP_AccelCal.h>
#include <AP_InertialSensor/AP_InertialSensor.h>
#include <AP_AHRS/AP_AHRS.h>
#include <AP_Mission/AP_Mission.h>
#include <AP_Mission/AP_Mission_ChangeDetector.h>
#include <AC_AttitudeControl/AC_AttitudeControl_Multi.h>
#include <AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.h>
#include <AC_AttitudeControl/AC_AttitudeControl_Heli.h>
#include <AC_AttitudeControl/AC_PosControl.h>
#include <AC_AttitudeControl/AC_CommandModel.h>
#include <AP_Motors/AP_Motors.h>
#include <Filter/Filter.h>
#include <AP_Vehicle/AP_Vehicle.h>
#include <AC_WPNav/AC_WPNav.h>
#include <AC_WPNav/AC_Loiter.h>
#include <AC_WPNav/AC_Circle.h>
#include <AP_Declination/AP_Declination.h>
#include <AP_RCMapper/AP_RCMapper.h>
#include <AP_BattMonitor/AP_BattMonitor.h>
#include <AP_LandingGear/AP_LandingGear.h>
#include <AC_InputManager/AC_InputManager.h>
#include <AC_InputManager/AC_InputManager_Heli.h>
#include <AP_Arming/AP_Arming.h>
#include <AP_SmartRTL/AP_SmartRTL.h>
#include <AP_TempCalibration/AP_TempCalibration.h>
#include <AC_AutoTune/AC_AutoTune_Multi.h>
#include <AC_AutoTune/AC_AutoTune_Heli.h>
#include <AP_Parachute/AP_Parachute.h>
#include <AC_Sprayer/AC_Sprayer.h>
#include <AP_Avoidance/AP_Avoidance.h>
#include <AP_ADSB/AP_ADSB.h>
#include <AP_Proximity/AP_Proximity.h>
#include <AC_PrecLand/AC_PrecLand_config.h>
#include <AP_OpticalFlow/AP_OpticalFlow.h>
#include <AP_Winch/AP_Winch_config.h>
#include <AP_SurfaceDistance/AP_SurfaceDistance.h>
#include "defines.h"
#include "config.h"
#if FRAME_CONFIG == HELI_FRAME
#define MOTOR_CLASS AP_MotorsHeli
#else
#define MOTOR_CLASS AP_MotorsMulticopter
#endif
#if MODE_AUTOROTATE_ENABLED
#include <AC_Autorotation/AC_Autorotation.h>
#endif
#include "RC_Channel_Copter.h"
#include "GCS_MAVLink_Copter.h"
#include "GCS_Copter.h"
#include "AP_Rally.h"
#include "AP_Arming_Copter.h"
#include <AP_ExternalControl/AP_ExternalControl_config.h>
#if AP_EXTERNAL_CONTROL_ENABLED
#include "AP_ExternalControl_Copter.h"
#endif
#include <AP_Beacon/AP_Beacon_config.h>
#if AP_BEACON_ENABLED
#include <AP_Beacon/AP_Beacon.h>
#endif
#if AP_AVOIDANCE_ENABLED
#include <AC_Avoidance/AC_Avoid.h>
#endif
#if AP_OAPATHPLANNER_ENABLED
#include <AC_WPNav/AC_WPNav_OA.h>
#include <AC_Avoidance/AP_OAPathPlanner.h>
#endif
#if AC_PRECLAND_ENABLED
# include <AC_PrecLand/AC_PrecLand.h>
# include <AC_PrecLand/AC_PrecLand_StateMachine.h>
#endif
#if MODE_FOLLOW_ENABLED
# include <AP_Follow/AP_Follow.h>
#endif
#if AP_TERRAIN_AVAILABLE
# include <AP_Terrain/AP_Terrain.h>
#endif
#if AP_RANGEFINDER_ENABLED
# include <AP_RangeFinder/AP_RangeFinder.h>
#endif
#include <AP_Mount/AP_Mount.h>
#include <AP_Camera/AP_Camera.h>
#if HAL_BUTTON_ENABLED
# include <AP_Button/AP_Button.h>
#endif
#if OSD_ENABLED || OSD_PARAM_ENABLED
#include <AP_OSD/AP_OSD.h>
#endif
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
# include "afs_copter.h"
#endif
#if TOY_MODE_ENABLED
# include "toy_mode.h"
#endif
#if AP_WINCH_ENABLED
# include <AP_Winch/AP_Winch.h>
#endif
#include <AP_RPM/AP_RPM.h>
#if AP_SCRIPTING_ENABLED
#include <AP_Scripting/AP_Scripting.h>
#endif
#if AC_CUSTOMCONTROL_MULTI_ENABLED
#include <AC_CustomControl/AC_CustomControl.h>
#endif
#if AP_AVOIDANCE_ENABLED && !AP_FENCE_ENABLED
#error AC_Avoidance relies on AP_FENCE_ENABLED which is disabled
#endif
#if AP_OAPATHPLANNER_ENABLED && !AP_FENCE_ENABLED
#error AP_OAPathPlanner relies on AP_FENCE_ENABLED which is disabled
#endif
#if MODE_AUTOROTATE_ENABLED && !AP_RPM_ENABLED
#error AC_Autorotation relies on AP_RPM_ENABLED which is disabled
#endif
#if HAL_ADSB_ENABLED
#include "avoidance_adsb.h"
#endif
#include "Parameters.h"
#if USER_PARAMS_ENABLED
#include "UserParameters.h"
#endif
#include "mode.h"
class Copter : public AP_Vehicle {
public:
friend class GCS_MAVLINK_Copter;
friend class GCS_Copter;
friend class AP_Rally_Copter;
friend class Parameters;
friend class ParametersG2;
friend class AP_Avoidance_Copter;
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
friend class AP_AdvancedFailsafe_Copter;
#endif
friend class AP_Arming_Copter;
#if AP_EXTERNAL_CONTROL_ENABLED
friend class AP_ExternalControl_Copter;
#endif
friend class ToyMode;
friend class RC_Channel_Copter;
friend class RC_Channels_Copter;
friend class AutoTune;
friend class Mode;
friend class ModeAcro;
friend class ModeAcro_Heli;
friend class ModeAltHold;
friend class ModeAuto;
friend class ModeAutoTune;
friend class ModeAvoidADSB;
friend class ModeBrake;
friend class ModeCircle;
friend class ModeDrift;
friend class ModeFlip;
friend class ModeFlowHold;
friend class ModeFollow;
friend class ModeGuided;
friend class ModeLand;
friend class ModeLoiter;
friend class ModePosHold;
friend class ModeRTL;
friend class ModeSmartRTL;
friend class ModeSport;
friend class ModeStabilize;
friend class ModeStabilize_Heli;
friend class ModeSystemId;
friend class ModeThrow;
friend class ModeZigZag;
friend class ModeAutorotate;
friend class ModeTurtle;
friend class _AutoTakeoff;
friend class PayloadPlace;
Copter(void);
private:
Parameters g;
ParametersG2 g2;
uint8_t command_ack_counter;
RC_Channel *channel_roll;
RC_Channel *channel_pitch;
RC_Channel *channel_throttle;
RC_Channel *channel_yaw;
#if AP_RC_TRANSMITTER_TUNING_ENABLED
RC_Channel *rc_tuning;
RC_Channel *rc_tuning2;
#endif
AP_Int8 *flight_modes;
const uint8_t num_flight_modes = 6;
AP_SurfaceDistance rangefinder_state {ROTATION_PITCH_270, 0U};
AP_SurfaceDistance rangefinder_up_state {ROTATION_PITCH_90, 1U};
bool get_rangefinder_height_interpolated_m(float& ret) const;
#if AP_RANGEFINDER_ENABLED
class SurfaceTracking {
public:
void update_surface_offset();
void external_init();
bool get_target_dist_for_logging(float &target_dist_m) const;
float get_dist_for_logging() const;
void invalidate_for_logging() { valid_for_logging = false; }
enum class Surface {
NONE = 0,
GROUND = 1,
CEILING = 2
};
void set_surface(Surface new_surface);
void init(Surface surf) { surface = surf; }
private:
Surface surface;
uint32_t last_update_ms;
uint32_t last_glitch_cleared_ms;
bool valid_for_logging;
bool reset_target;
} surface_tracking;
#endif
AP_AHRS_View *ahrs_view;
AP_Arming_Copter arming;
#if AP_OPTICALFLOW_ENABLED
AP_OpticalFlow optflow;
#endif
#if AP_EXTERNAL_CONTROL_ENABLED
AP_ExternalControl_Copter external_control;
#endif
uint32_t ekfYawReset_ms;
int8_t ekf_primary_core;
struct {
bool high_vibes;
uint32_t start_ms;
uint32_t clear_ms;
} vibration_check;
LowPassFilterFloat pos_variance_filt;
LowPassFilterFloat vel_variance_filt;
bool variances_valid;
uint32_t last_ekf_check_us;
uint32_t takeoff_check_warning_ms;
GCS_Copter _gcs;
GCS_Copter &gcs() { return _gcs; }
#ifdef USERHOOK_VARIABLES
# include USERHOOK_VARIABLES
#endif
uint32_t ap_value() const;
struct PACKED {
bool unused1;
bool unused_was_simple_mode_byte1;
bool unused_was_simple_mode_byte2;
bool pre_arm_rc_check;
bool pre_arm_check;
bool auto_armed;
bool unused_log_started;
bool land_complete;
bool new_radio_frame;
bool unused_usb_connected;
bool unused_receiver_present;
bool compass_mot;
bool motor_test;
bool initialised;
bool land_complete_maybe;
bool throttle_zero;
bool system_time_set_unused;
bool gps_glitching;
bool using_interlock;
bool land_repo_active;
bool motor_interlock_switch;
bool in_arming_delay;
bool initialised_params;
bool unused_compass_init_location;
bool unused2_aux_switch_rc_override_allowed;
bool armed_with_airmode_switch;
bool prec_land_active;
} ap;
AirMode air_mode;
bool force_flying;
Mode *flightmode;
RCMapper rcmap;
float arming_altitude_m;
struct {
uint32_t terrain_first_failure_ms;
uint32_t terrain_last_failure_ms;
int8_t radio_counter;
uint8_t radio : 1;
uint8_t gcs : 1;
uint8_t ekf : 1;
uint8_t terrain : 1;
uint8_t adsb : 1;
uint8_t deadreckon : 1;
} failsafe;
bool any_failsafe_triggered() const {
return failsafe.radio || battery.has_failsafed() || failsafe.gcs || failsafe.ekf || failsafe.terrain || failsafe.adsb || failsafe.deadreckon;
}
struct {
bool active;
bool timeout;
uint32_t start_ms;
} dead_reckoning;
MOTOR_CLASS *motors;
const struct AP_Param::GroupInfo *motors_var_info;
float _home_bearing_rad;
float _home_distance_m;
enum class SimpleMode {
NONE = 0,
SIMPLE = 1,
SUPERSIMPLE = 2,
} simple_mode;
float simple_cos_yaw;
float simple_sin_yaw;
float super_simple_last_bearing_rad;
float super_simple_cos_yaw;
float super_simple_sin_yaw;
float initial_armed_bearing_rad;
AP_BattMonitor battery{MASK_LOG_CURRENT,
FUNCTOR_BIND_MEMBER(&Copter::handle_battery_failsafe, void, const char*, const int8_t),
_failsafe_priorities};
#if OSD_ENABLED || OSD_PARAM_ENABLED
AP_OSD osd;
#endif
float baro_alt_m;
LowPassFilterVector3f land_accel_ef_filter;
LowPassFilterFloat rc_throttle_control_in_filter;
Location current_loc;
AC_AttitudeControl *attitude_control;
const struct AP_Param::GroupInfo *attitude_control_var_info;
AC_PosControl *pos_control;
AC_WPNav *wp_nav;
AC_Loiter *loiter_nav;
#if AC_CUSTOMCONTROL_MULTI_ENABLED
AC_CustomControl custom_control{ahrs_view, attitude_control, motors};
#endif
#if MODE_CIRCLE_ENABLED
AC_Circle *circle_nav;
#endif
uint32_t arm_time_ms;
#if AP_CAMERA_ENABLED
AP_Camera camera{MASK_LOG_CAMERA};
#endif
#if HAL_MOUNT_ENABLED
AP_Mount camera_mount;
#endif
#if AP_AVOIDANCE_ENABLED
AC_Avoid avoid;
#endif
#if HAL_RALLY_ENABLED
AP_Rally_Copter rally;
#endif
#if HAL_SPRAYER_ENABLED
AC_Sprayer sprayer;
#endif
#if HAL_PARACHUTE_ENABLED
AP_Parachute parachute;
#endif
#if AP_LANDINGGEAR_ENABLED
AP_LandingGear landinggear;
#endif
#if AP_TERRAIN_AVAILABLE
AP_Terrain terrain;
#endif
#if AC_PRECLAND_ENABLED
AC_PrecLand precland;
AC_PrecLand_StateMachine precland_statemachine;
#endif
#if FRAME_CONFIG == HELI_FRAME
AC_InputManager_Heli input_manager;
#endif
#if HAL_ADSB_ENABLED
AP_ADSB adsb;
#endif
#if AP_ADSB_AVOIDANCE_ENABLED
AP_Avoidance_Copter avoidance_adsb{adsb};
#endif
uint32_t last_radio_update_ms;
uint32_t esc_calibration_notify_update_ms;
AP_Param param_loader;
#if FRAME_CONFIG == HELI_FRAME
typedef struct {
bool dynamic_flight ;
bool coll_stk_low ;
} heli_flags_t;
heli_flags_t heli_flags;
int16_t hover_roll_trim_scalar_slew;
#endif
struct {
bool takeoff_expected;
bool touchdown_expected;
uint32_t takeoff_time_ms;
float takeoff_alt_m;
} gndeffect_state;
bool standby_active;
static const AP_Scheduler::Task scheduler_tasks[];
static const AP_Param::Info var_info[];
static const struct LogStructure log_structure[];
enum ESCCalibrationModes : uint8_t {
ESCCAL_NONE = 0,
ESCCAL_PASSTHROUGH_IF_THROTTLE_HIGH = 1,
ESCCAL_PASSTHROUGH_ALWAYS = 2,
ESCCAL_AUTO = 3,
ESCCAL_DISABLED = 9,
};
enum class FailsafeAction : uint8_t {
NONE = 0,
LAND = 1,
RTL = 2,
SMARTRTL = 3,
SMARTRTL_LAND = 4,
TERMINATE = 5,
AUTO_DO_LAND_START = 6,
BRAKE_LAND = 7
};
enum class FailsafeOption {
RC_CONTINUE_IF_AUTO = (1<<0),
GCS_CONTINUE_IF_AUTO = (1<<1),
RC_CONTINUE_IF_GUIDED = (1<<2),
CONTINUE_IF_LANDING = (1<<3),
GCS_CONTINUE_IF_PILOT_CONTROL = (1<<4),
RELEASE_GRIPPER = (1<<5),
};
enum class FlightOption : uint32_t {
DISABLE_THRUST_LOSS_CHECK = (1<<0),
DISABLE_YAW_IMBALANCE_WARNING = (1<<1),
RELEASE_GRIPPER_ON_THRUST_LOSS = (1<<2),
};
enum class FastRateType : uint8_t {
FAST_RATE_DISABLED = 0,
FAST_RATE_DYNAMIC = 1,
FAST_RATE_FIXED_ARMED = 2,
FAST_RATE_FIXED = 3,
};
FastRateType get_fast_rate_type() const { return FastRateType(g2.att_enable.get()); }
bool option_is_enabled(FlightOption option) const {
return (g2.flight_options & uint32_t(option)) != 0;
}
static constexpr int8_t _failsafe_priorities[] = {
(int8_t)FailsafeAction::TERMINATE,
(int8_t)FailsafeAction::LAND,
(int8_t)FailsafeAction::RTL,
(int8_t)FailsafeAction::SMARTRTL_LAND,
(int8_t)FailsafeAction::SMARTRTL,
(int8_t)FailsafeAction::NONE,
-1
};
#define FAILSAFE_LAND_PRIORITY 1
static_assert(_failsafe_priorities[FAILSAFE_LAND_PRIORITY] == (int8_t)FailsafeAction::LAND,
"FAILSAFE_LAND_PRIORITY must match the entry in _failsafe_priorities");
static_assert(_failsafe_priorities[ARRAY_SIZE(_failsafe_priorities) - 1] == -1,
"_failsafe_priorities is missing the sentinel");
void set_auto_armed(bool b);
void set_simple_mode(SimpleMode b);
void set_failsafe_radio(bool b);
void set_failsafe_gcs(bool b);
void update_using_interlock();
void get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
uint8_t &task_count,
uint32_t &log_bit) override;
#if AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED
#if MODE_GUIDED_ENABLED
bool set_target_location(const Location& target_loc) override;
bool start_takeoff(const float alt_m) override;
#endif
#endif
#if AP_SCRIPTING_ENABLED
#if MODE_GUIDED_ENABLED
bool get_target_location(Location& target_loc) override;
bool update_target_location(const Location &old_loc, const Location &new_loc) override;
bool set_target_pos_NED(const Vector3f& target_pos, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool yaw_relative, bool is_terrain_alt) override;
bool set_target_posvel_NED(const Vector3f& target_pos, const Vector3f& target_vel) override;
bool set_target_posvelaccel_NED(const Vector3f& target_pos, const Vector3f& target_vel, const Vector3f& target_accel, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool yaw_relative) override;
bool set_target_velocity_NED(const Vector3f& vel_ned, bool align_yaw_to_target) override;
bool set_target_velaccel_NED(const Vector3f& target_vel, const Vector3f& target_accel, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool relative_yaw) override;
bool set_target_angle_and_climbrate(float roll_deg, float pitch_deg, float yaw_deg, float climb_rate_ms, bool use_yaw_rate, float yaw_rate_degs) override;
bool set_target_rate_and_throttle(float roll_rate_dps, float pitch_rate_dps, float yaw_rate_dps, float throttle) override;
bool set_target_angle_and_rate_and_throttle(float roll_deg, float pitch_deg, float yaw_deg, float roll_rate_degs, float pitch_rate_degs, float yaw_rate_degs, float throttle) override;
AP_Vehicle::custom_mode_state* register_custom_mode(const uint8_t number, const char* full_name, const char* short_name) override;
#endif
#if MODE_CIRCLE_ENABLED
bool get_circle_radius(float &radius_m) override;
bool set_circle_rate(float rate_dps) override;
#endif
bool set_desired_speed(float speed) override;
#if MODE_AUTO_ENABLED
bool nav_scripting_enable(uint8_t mode) override;
bool nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2, int16_t &arg3, int16_t &arg4) override;
void nav_script_time_done(uint16_t id) override;
#endif
bool has_ekf_failsafed() const override;
#endif
bool is_landing() const override;
bool is_taking_off() const override;
void rc_loop();
void throttle_loop();
void update_batt_compass(void);
void loop_rate_logging();
void ten_hz_logging_loop();
void twentyfive_hz_logging();
void three_hz_loop();
void one_hz_loop();
void init_simple_bearing();
void update_simple_mode(void);
void update_super_simple_bearing(bool force_update);
void read_AHRS(void);
void update_altitude();
bool get_wp_distance_m(float &distance) const override;
bool get_wp_bearing_deg(float &bearing) const override;
bool get_wp_crosstrack_error_m(float &xtrack_error) const override;
bool get_rate_ef_targets(Vector3f& rate_ef_targets) const override;
void update_throttle_hover();
float get_pilot_desired_climb_rate_ms();
float get_non_takeoff_throttle();
void set_accel_throttle_I_from_pilot_throttle();
uint16_t get_pilot_speed_dn() const;
void run_rate_controller_main();
struct RateControllerRates {
uint8_t fast_logging_rate;
uint8_t medium_logging_rate;
uint8_t filter_rate;
uint8_t main_loop_rate;
};
uint8_t calc_gyro_decimation(uint8_t gyro_decimation, uint16_t rate_hz);
void rate_controller_thread();
void rate_controller_filter_update();
void rate_controller_log_update();
void rate_controller_set_rates(uint8_t rate_decimation, RateControllerRates& rates, bool warn_cpu_high);
void enable_fast_rate_loop(uint8_t rate_decimation, RateControllerRates& rates);
void disable_fast_rate_loop(RateControllerRates& rates);
void update_dynamic_notch_at_specified_rate_main();
#if AC_CUSTOMCONTROL_MULTI_ENABLED
void run_custom_controller() { custom_control.update(); }
#endif
void low_alt_avoidance();
#if HAL_ADSB_ENABLED || AP_ADSB_AVOIDANCE_ENABLED
void avoidance_adsb_update(void);
#endif
void update_ground_effect_detector(void);
void update_ekf_terrain_height_stable();
void update_home_from_EKF();
void set_home_to_current_location_inflight();
bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED;
bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED;
MAV_RESULT mavlink_compassmot(const GCS_MAVLINK &gcs_chan);
void crash_check();
void thrust_loss_check();
void yaw_imbalance_check();
LowPassFilterFloat yaw_I_filt{0.05f};
uint32_t last_yaw_warn_ms;
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 failsafe_ekf_recheck();
void check_ekf_reset();
void check_vibration();
void esc_calibration_startup_check();
void esc_calibration_passthrough();
void esc_calibration_auto();
void esc_calibration_notify();
void esc_calibration_setup();
bool failsafe_option(FailsafeOption opt) const;
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_on_event(void);
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 failsafe_deadreckon_check();
void set_mode_RTL_or_land_with_pause(ModeReason reason);
void set_mode_SmartRTL_or_RTL(ModeReason reason);
void set_mode_SmartRTL_or_land_with_pause(ModeReason reason);
void set_mode_auto_do_land_start_or_RTL(ModeReason reason);
void set_mode_brake_or_land_with_pause(ModeReason reason);
bool should_disarm_on_failsafe();
void do_failsafe_action(FailsafeAction action, ModeReason reason);
void announce_failsafe(const char *type, const char *action_undertaken=nullptr);
void failsafe_enable();
void failsafe_disable();
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
void afs_fs_check(void);
#endif
#if AP_FENCE_ENABLED
void fence_check();
void fence_checks_async() override;
#endif
void heli_init();
void check_dynamic_flight(void);
bool should_use_landing_swash() const;
void update_heli_control_dynamics(void);
void heli_update_landing_swash();
float get_pilot_desired_rotor_speed() const;
void heli_update_rotor_speed_targets();
void heli_update_autorotation();
void update_collective_low_flag(int16_t throttle_control);
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_mix();
bool get_force_flying() const;
#if HAL_LOGGING_ENABLED
enum class LandDetectorLoggingFlag : uint16_t {
LANDED = 1U << 0,
LANDED_MAYBE = 1U << 1,
LANDING = 1U << 2,
STANDBY_ACTIVE = 1U << 3,
WOW = 1U << 4,
RANGEFINDER_BELOW_2M = 1U << 5,
DESCENT_RATE_LOW = 1U << 6,
ACCEL_STATIONARY = 1U << 7,
LARGE_ANGLE_ERROR = 1U << 8,
LARGE_ANGLE_REQUEST = 1U << 8,
MOTOR_AT_LOWER_LIMIT = 1U << 9,
THROTTLE_MIX_AT_MIN = 1U << 10,
};
struct {
uint32_t last_logged_ms;
uint32_t last_logged_count;
uint16_t last_logged_flags;
} land_detector;
void Log_LDET(uint16_t logging_flags, uint32_t land_detector_count);
#endif
#if AP_LANDINGGEAR_ENABLED
void landinggear_update();
#endif
void standby_update();
#if HAL_LOGGING_ENABLED
const AP_Int32 &get_log_bitmask() override { return g.log_bitmask; }
const struct LogStructure *get_log_structures() const override {
return log_structure;
}
uint8_t get_num_log_structures() const override;
void Log_Write_Control_Tuning();
void Log_Write_Attitude();
void Log_Write_Rate();
void Log_Write_EKF_POS();
void Log_Write_PIDS();
void Log_Write_Data(LogDataID id, int32_t value);
void Log_Write_Data(LogDataID id, uint32_t value);
void Log_Write_Data(LogDataID id, int16_t value);
void Log_Write_Data(LogDataID id, uint16_t value);
void Log_Write_Data(LogDataID id, float value);
void Log_Write_PTUN(uint8_t param, float tuning_val, float tune_min, float tune_max, float norm_in);
void Log_Video_Stabilisation();
void Log_Write_Guided_Position_Target(ModeGuided::SubMode submode, const Vector3p& pos_target_ned_m, bool is_terrain_alt, const Vector3f& vel_target_ms, const Vector3f& accel_target_mss);
void Log_Write_Guided_Attitude_Target(ModeGuided::SubMode submode, float roll, float pitch, float yaw, const Vector3f &ang_vel, float thrust, float climb_rate);
void Log_Write_SysID_Setup(uint8_t systemID_axis, float waveform_magnitude, float frequency_start, float frequency_stop, float time_fade_in, float time_const_freq, float time_record, float time_fade_out);
void Log_Write_SysID_Data(float waveform_time, float waveform_sample, float waveform_freq, float angle_x, float angle_y, float angle_z, float accel_x, float accel_y, float accel_z);
void Log_Write_Vehicle_Startup_Messages();
void Log_Write_Rate_Thread_Dt(float dt, float dtAvg, float dtMax, float dtMin);
#endif
bool set_mode(Mode::Number mode, ModeReason reason);
bool set_mode(const uint8_t new_mode, const ModeReason reason) override;
ModeReason _last_reason;
void mode_change_failed(const Mode *mode, const char *reason);
uint8_t get_mode() const override { return (uint8_t)flightmode->mode_number(); }
bool current_mode_requires_mission() const override;
void update_flight_mode();
void notify_flight_mode();
bool gcs_mode_enabled(const Mode::Number mode_num);
void set_mode_land_with_pause(ModeReason reason);
bool landing_with_GPS();
void motor_test_output();
bool mavlink_motor_control_check(const GCS_MAVLINK &gcs_chan, bool check_rc, const char* mode);
MAV_RESULT mavlink_motor_test_start(const GCS_MAVLINK &gcs_chan, uint8_t motor_seq, uint8_t throttle_type, float throttle_value, float timeout_sec, uint8_t motor_count);
void motor_test_stop();
void auto_disarm_check();
void motors_output(bool full_push = true);
void motors_output_main();
void lost_vehicle_check();
void run_nav_updates(void);
float home_bearing_rad();
float home_distance_m();
void load_parameters(void) override;
void convert_pid_parameters(void);
#if HAL_PROXIMITY_ENABLED
void convert_prx_parameters();
#endif
void init_precland();
void update_precland();
void default_dead_zones();
void init_rc_in();
void init_rc_out();
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() const;
bool rangefinder_up_ok() const;
void update_rangefinder_terrain_offset();
void takeoff_check();
void init_ardupilot() override;
void startup_INS_ground();
bool position_ok() const;
bool ekf_has_absolute_position() const;
bool ekf_has_relative_position() const;
bool ekf_alt_ok() const;
void update_auto_armed();
bool should_log(uint32_t mask);
const char* get_frame_string() const;
void allocate_motors(void);
bool is_tradheli() const;
void terrain_update();
void terrain_logging();
#if AP_RC_TRANSMITTER_TUNING_ENABLED
void tuning();
void tuning(const class RC_Channel *tuning_ch, int8_t tuning_param, float tuning_min, float tuning_max);
bool being_tuned(int8_t tuning_param) const;
#endif
void userhook_init();
void userhook_FastLoop();
void userhook_50Hz();
void userhook_MediumLoop();
void userhook_SlowLoop();
void userhook_SuperSlowLoop();
void userhook_auxSwitch1(const RC_Channel::AuxSwitchPos ch_flag);
void userhook_auxSwitch2(const RC_Channel::AuxSwitchPos ch_flag);
void userhook_auxSwitch3(const RC_Channel::AuxSwitchPos ch_flag);
#if MODE_ACRO_ENABLED
#if FRAME_CONFIG == HELI_FRAME
ModeAcro_Heli mode_acro;
#else
ModeAcro mode_acro;
#endif
#endif
ModeAltHold mode_althold;
#if MODE_AUTO_ENABLED
ModeAuto mode_auto;
#endif
#if AUTOTUNE_ENABLED
ModeAutoTune mode_autotune;
#endif
#if MODE_BRAKE_ENABLED
ModeBrake mode_brake;
#endif
#if MODE_CIRCLE_ENABLED
ModeCircle mode_circle;
#endif
#if MODE_DRIFT_ENABLED
ModeDrift mode_drift;
#endif
#if MODE_FLIP_ENABLED
ModeFlip mode_flip;
#endif
#if MODE_FOLLOW_ENABLED
ModeFollow mode_follow;
#endif
#if MODE_GUIDED_ENABLED
ModeGuided mode_guided;
#if AP_SCRIPTING_ENABLED
ModeGuidedCustom *mode_guided_custom[5];
#endif
#endif
ModeLand mode_land;
#if MODE_LOITER_ENABLED
ModeLoiter mode_loiter;
#endif
#if MODE_POSHOLD_ENABLED
ModePosHold mode_poshold;
#endif
#if MODE_RTL_ENABLED
ModeRTL mode_rtl;
#endif
#if FRAME_CONFIG == HELI_FRAME
ModeStabilize_Heli mode_stabilize;
#else
ModeStabilize mode_stabilize;
#endif
#if MODE_SPORT_ENABLED
ModeSport mode_sport;
#endif
#if MODE_SYSTEMID_ENABLED
ModeSystemId mode_systemid;
#endif
#if AP_ADSB_AVOIDANCE_ENABLED
ModeAvoidADSB mode_avoid_adsb;
#endif
#if MODE_THROW_ENABLED
ModeThrow mode_throw;
#endif
#if MODE_GUIDED_NOGPS_ENABLED
ModeGuidedNoGPS mode_guided_nogps;
#endif
#if MODE_SMARTRTL_ENABLED
ModeSmartRTL mode_smartrtl;
#endif
#if MODE_FLOWHOLD_ENABLED
ModeFlowHold mode_flowhold;
#endif
#if MODE_ZIGZAG_ENABLED
ModeZigZag mode_zigzag;
#endif
#if MODE_AUTOROTATE_ENABLED
ModeAutorotate mode_autorotate;
#endif
#if MODE_TURTLE_ENABLED
ModeTurtle mode_turtle;
#endif
Mode *mode_from_mode_num(const Mode::Number mode);
void exit_mode(Mode *&old_flightmode, Mode *&new_flightmode);
bool started_rate_thread;
bool using_rate_thread;
public:
void failsafe_check();
};
extern Copter copter;
using AP_HAL::millis;
using AP_HAL::micros;