7 #ifndef AP_MOTORS_DENSITY_COMP 8 #define AP_MOTORS_DENSITY_COMP 1 11 #define AP_MOTORS_DEFAULT_MID_THROTTLE 500 13 #define AP_MOTORS_SPIN_WHEN_ARMED 70 // spin motors at this PWM value when armed 14 #define AP_MOTORS_YAW_HEADROOM_DEFAULT 200 15 #define AP_MOTORS_THST_EXPO_DEFAULT 0.65f // set to 0 for linear and 1 for second order approximation 16 #define AP_MOTORS_THST_HOVER_DEFAULT 0.35f // the estimated hover throttle, 0 ~ 1 17 #define AP_MOTORS_THST_HOVER_TC 10.0f // time constant used to update estimated hover throttle, 0 ~ 1 18 #define AP_MOTORS_THST_HOVER_MIN 0.125f // minimum possible hover throttle 19 #define AP_MOTORS_THST_HOVER_MAX 0.6875f // maximum possible hover throttle 20 #define AP_MOTORS_SPIN_MIN_DEFAULT 0.15f // throttle out ratio which produces the minimum thrust. (i.e. 0 ~ 1 ) of the full throttle range 21 #define AP_MOTORS_SPIN_MAX_DEFAULT 0.95f // throttle out ratio which produces the maximum thrust. (i.e. 0 ~ 1 ) of the full throttle range 22 #define AP_MOTORS_SPIN_ARM_DEFAULT 0.10f // throttle out ratio which produces the armed spin rate. (i.e. 0 ~ 1 ) of the full throttle range 23 #define AP_MOTORS_BAT_VOLT_MAX_DEFAULT 0.0f // voltage limiting max default 24 #define AP_MOTORS_BAT_VOLT_MIN_DEFAULT 0.0f // voltage limiting min default (voltage dropping below this level will have no effect) 25 #define AP_MOTORS_BAT_CURR_MAX_DEFAULT 0.0f // current limiting max default 26 #define AP_MOTORS_BAT_CURR_TC_DEFAULT 5.0f // Time constant used to limit the maximum current 27 #define AP_MOTORS_BATT_VOLT_FILT_HZ 0.5f // battery voltage filtered at 0.5hz 30 #define AP_MOTORS_SPOOL_UP_TIME_DEFAULT 0.5f // time (in seconds) for throttle to increase from zero to min throttle, and min throttle to full throttle.
bool spool_up_complete() const
AP_Int8 _throttle_hover_learn
int16_t get_pwm_output_min() const
static const struct AP_Param::GroupInfo var_info[]
int16_t get_pwm_output_max() const
int16_t _throttle_radio_max
AP_Float _thrust_curve_expo
#define AP_MOTORS_SPEED_DEFAULT
FUNCTOR_TYPEDEF(thrust_compensation_fn_t, void, float *, uint8_t)
uint16_t _disarm_safety_timer
AP_Int8 _disarm_disable_pwm
virtual void thrust_compensation(void)
virtual void output_to_motors()=0
void save_params_on_disarm()
float apply_thrust_curve_and_volt_scaling(float thrust) const
AP_Float _batt_voltage_max
virtual float get_throttle_hover() const
bool motor_enabled[AP_MOTORS_MAX_NUM_MOTORS]
float get_throttle_thrust_max() const
int16_t _throttle_radio_min
void update_throttle_hover(float dt)
AP_MotorsMulticopter(uint16_t loop_rate, uint16_t speed_hz=AP_MOTORS_SPEED_DEFAULT)
AP_Float _batt_current_max
float get_batt_voltage_filt() const
float _throttle_thrust_max
void set_throttle_range(int16_t radio_min, int16_t radio_max)
virtual void update_throttle_filter()
void set_throttle_passthrough_for_esc_calibration(float throttle_input)
spool_up_down_mode _spool_mode
int16_t calc_spin_up_to_pwm() const
thrust_compensation_fn_t _thrust_compensation_callback
float get_compensation_gain() const
virtual float get_current_limit_max_throttle()
AP_Float _batt_voltage_min
int16_t calc_thrust_to_pwm(float thrust_in) const
virtual void output_boost_throttle(void)
void set_thrust_compensation_callback(thrust_compensation_fn_t callback)
AP_Float _yaw_servo_angle_max_deg
void set_yaw_headroom(int16_t pwm)
void update_lift_max_from_batt_voltage()
#define AP_MOTORS_MAX_NUM_MOTORS
LowPassFilterFloat _batt_voltage_filt
float get_throttle_limit() const
AP_Float _batt_current_time_constant
virtual void output_motor_mask(float thrust, uint8_t mask)