APM:Libraries
AP_MotorsMulticopter.h
Go to the documentation of this file.
1 #pragma once
4 
5 #include "AP_Motors_Class.h"
6 
7 #ifndef AP_MOTORS_DENSITY_COMP
8 #define AP_MOTORS_DENSITY_COMP 1
9 #endif
10 
11 #define AP_MOTORS_DEFAULT_MID_THROTTLE 500
12 
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
28 
29 // spool definition
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.
31 
34 public:
35 
36  // Constructor
37  AP_MotorsMulticopter(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT);
38 
39  // output - sends commands to the motors
40  virtual void output();
41 
42  // output_min - sends minimum values out to the motors
43  void output_min();
44 
45  // set_yaw_headroom - set yaw headroom (yaw is given at least this amount of pwm)
46  void set_yaw_headroom(int16_t pwm) { _yaw_headroom = pwm; }
47 
48  // set_throttle_range - sets the minimum throttle that will be sent to the engines when they're not off (i.e. to prevents issues with some motors spinning and some not at very low throttle)
49  // also sets minimum and maximum pwm values that will be sent to the motors
50  void set_throttle_range(int16_t radio_min, int16_t radio_max);
51 
52  // update estimated throttle required to hover
53  void update_throttle_hover(float dt);
54  virtual float get_throttle_hover() const { return _throttle_hover; }
55 
56  // spool up states
58  SHUT_DOWN = 0, // all motors stop
59  SPIN_WHEN_ARMED = 1, // all motors at spin when armed
60  SPOOL_UP = 2, // increasing maximum throttle while stabilizing
61  THROTTLE_UNLIMITED = 3, // throttle is no longer constrained by start up procedure
62  SPOOL_DOWN = 4, // decreasing maximum throttle while stabilizing
63  };
64 
65  // passes throttle directly to all motors for ESC calibration.
66  // throttle_input is in the range of 0 ~ 1 where 0 will send get_pwm_output_min() and 1 will send get_pwm_output_max()
67  void set_throttle_passthrough_for_esc_calibration(float throttle_input);
68 
69  // get_lift_max - get maximum lift ratio - for logging purposes only
70  float get_lift_max() { return _lift_max; }
71 
72  // get_batt_voltage_filt - get battery voltage ratio - for logging purposes only
73  float get_batt_voltage_filt() const { return _batt_voltage_filt.get(); }
74 
75  // get throttle limit imposed by battery current limiting. This is a number from 0 ~ 1 where 0 means hover throttle, 1 means full throttle (i.e. not limited)
76  float get_throttle_limit() const { return _throttle_limit; }
77 
78  // returns maximum thrust in the range 0 to 1
80 
81  // return true if spool up is complete
82  bool spool_up_complete() const { return _spool_mode == THROTTLE_UNLIMITED; }
83 
84  // output a thrust to all motors that match a given motor
85  // mask. This is used to control tiltrotor motors in forward
86  // flight. Thrust is in the range 0 to 1
87  virtual void output_motor_mask(float thrust, uint8_t mask);
88 
89  // get minimum or maximum pwm value that can be output to motors
90  int16_t get_pwm_output_min() const;
91  int16_t get_pwm_output_max() const;
92 
93  // set thrust compensation callback
94  FUNCTOR_TYPEDEF(thrust_compensation_fn_t, void, float *, uint8_t);
95  void set_thrust_compensation_callback(thrust_compensation_fn_t callback) {
97  }
98 
99  // var_info for holding Parameter information
100  static const struct AP_Param::GroupInfo var_info[];
101 
102 protected:
103 
104  // run spool logic
105  void output_logic();
106 
107  // output_to_motors - sends commands to the motors
108  virtual void output_to_motors() = 0;
109 
110  // update the throttle input filter
111  virtual void update_throttle_filter();
112 
113  // return current_limit as a number from 0 ~ 1 in the range throttle_min to throttle_max
114  virtual float get_current_limit_max_throttle();
115 
116  // apply_thrust_curve_and_volt_scaling - returns throttle in the range 0 ~ 1
117  float apply_thrust_curve_and_volt_scaling(float thrust) const;
118 
119  // update_lift_max_from_batt_voltage - used for voltage compensation
121 
122  // return gain scheduling gain based on voltage and air density
123  float get_compensation_gain() const;
124 
125  // convert thrust (0~1) range back to pwm range
126  int16_t calc_thrust_to_pwm(float thrust_in) const;
127 
128  // calculate spin up to pwm range
129  int16_t calc_spin_up_to_pwm() const;
130 
131  // apply any thrust compensation for the frame
132  virtual void thrust_compensation(void) {}
133 
134  // output booster throttle, if any
135  virtual void output_boost_throttle(void);
136 
137  // save parameters as part of disarming
138  void save_params_on_disarm();
139 
140  // enum values for HOVER_LEARN parameter
141  enum HoverLearn {
145  };
146 
147  // parameters
148  AP_Int16 _yaw_headroom; // yaw control is given at least this pwm range
149  AP_Float _thrust_curve_expo; // curve used to linearize pwm to thrust conversion. set to 0 for linear and 1 for second order approximation
150  AP_Float _spin_min; // throttle out ratio which produces the minimum thrust. (i.e. 0 ~ 1 ) of the full throttle range
151  AP_Float _spin_max; // throttle out ratio which produces the maximum thrust. (i.e. 0 ~ 1 ) of the full throttle range
152  AP_Float _spin_arm; // throttle out ratio which produces the armed spin rate. (i.e. 0 ~ 1 ) of the full throttle range
153  AP_Float _batt_voltage_max; // maximum voltage used to scale lift
154  AP_Float _batt_voltage_min; // minimum voltage used to scale lift
155  AP_Float _batt_current_max; // current over which maximum throttle is limited
156  AP_Float _batt_current_time_constant; // Time constant used to limit the maximum current
157  AP_Int8 _batt_idx; // battery index used for compensation
158  AP_Int16 _pwm_min; // minimum PWM value that will ever be output to the motors (if 0, vehicle's throttle input channel's min pwm used)
159  AP_Int16 _pwm_max; // maximum PWM value that will ever be output to the motors (if 0, vehicle's throttle input channel's max pwm used)
160  AP_Float _throttle_hover; // estimated throttle required to hover throttle in the range 0 ~ 1
161  AP_Int8 _throttle_hover_learn; // enable/disabled hover thrust learning
162  AP_Int8 _disarm_disable_pwm; // disable PWM output while disarmed
163 
164  // Maximum lean angle of yaw servo in degrees. This is specific to tricopter
166 
167  // time to spool motors to min throttle
168  AP_Float _spool_up_time;
169 
170  // scaling for booster motor throttle
171  AP_Float _boost_scale;
172 
173  // motor output variables
174  bool motor_enabled[AP_MOTORS_MAX_NUM_MOTORS]; // true if motor is enabled
175  int16_t _throttle_radio_min; // minimum PWM from RC input's throttle channel (i.e. minimum PWM input from receiver, RC3_MIN)
176  int16_t _throttle_radio_max; // maximum PWM from RC input's throttle channel (i.e. maximum PWM input from receiver, RC3_MAX)
177 
178  // spool variables
179  spool_up_down_mode _spool_mode; // motor's current spool mode
180  float _spin_up_ratio; // throttle percentage (0 ~ 1) between zero and throttle_min
181 
182  // battery voltage, current and air pressure compensation variables
183  LowPassFilterFloat _batt_voltage_filt; // filtered battery voltage expressed as a percentage (0 ~ 1.0) of batt_voltage_max
184  float _lift_max; // maximum lift ratio from battery voltage
185  float _throttle_limit; // ratio of throttle limit between hover and maximum
186  float _throttle_thrust_max; // the maximum allowed throttle thrust 0.0 to 1.0 in the range throttle_min to throttle_max
188 
189  // vehicle supplied callback for thrust compensation. Used for tiltrotors and tiltwings
190  thrust_compensation_fn_t _thrust_compensation_callback;
191 };
int16_t get_pwm_output_min() const
static const struct AP_Param::GroupInfo var_info[]
int16_t get_pwm_output_max() const
#define AP_MOTORS_SPEED_DEFAULT
FUNCTOR_TYPEDEF(thrust_compensation_fn_t, void, float *, uint8_t)
static uint16_t pwm
Definition: RCOutput.cpp:20
virtual void thrust_compensation(void)
virtual void output_to_motors()=0
float apply_thrust_curve_and_volt_scaling(float thrust) const
virtual float get_throttle_hover() const
bool motor_enabled[AP_MOTORS_MAX_NUM_MOTORS]
float get_throttle_thrust_max() const
void update_throttle_hover(float dt)
AP_MotorsMulticopter(uint16_t loop_rate, uint16_t speed_hz=AP_MOTORS_SPEED_DEFAULT)
float get_batt_voltage_filt() const
void set_throttle_range(int16_t radio_min, int16_t radio_max)
const T & get() const
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
virtual float get_current_limit_max_throttle()
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)
void set_yaw_headroom(int16_t pwm)
#define AP_MOTORS_MAX_NUM_MOTORS
LowPassFilterFloat _batt_voltage_filt
float get_throttle_limit() const
virtual void output_motor_mask(float thrust, uint8_t mask)