mirror of https://github.com/ArduPilot/ardupilot
AP_MotorsMulticopter: throttle_radio_min, max to multicopter class
Moved in from Motors class, only ever used by multicopters No functional change
This commit is contained in:
parent
2c9a02066d
commit
420b90953c
|
@ -108,6 +108,8 @@ AP_MotorsMulticopter::AP_MotorsMulticopter(uint16_t loop_rate, uint16_t speed_hz
|
|||
_throttle_rpy_mix(AP_MOTORS_THR_LOW_CMP_DEFAULT),
|
||||
_min_throttle(AP_MOTORS_DEFAULT_MIN_THROTTLE),
|
||||
_hover_out(AP_MOTORS_DEFAULT_MID_THROTTLE),
|
||||
_throttle_radio_min(1100),
|
||||
_throttle_radio_max(1900),
|
||||
_batt_voltage_resting(0.0f),
|
||||
_batt_current_resting(0.0f),
|
||||
_batt_resistance(0.0f),
|
||||
|
|
|
@ -174,6 +174,8 @@ protected:
|
|||
float _throttle_rpy_mix; // mix between throttle and hover throttle for 0 to 1 and ratio above hover throttle for >1
|
||||
int16_t _min_throttle; // the minimum throttle to be sent to the motors when they're on (prevents motors stalling while flying)
|
||||
int16_t _hover_out; // the estimated hover throttle as pct * 10 (i.e. 0 ~ 1000)
|
||||
int16_t _throttle_radio_min; // minimum radio channel pwm
|
||||
int16_t _throttle_radio_max; // maximum radio channel pwm
|
||||
float _throttle_thrust_max; // the maximum allowed throttle thrust 0.0 to 1.0 in the range throttle_min to throttle_max
|
||||
|
||||
// spool variables
|
||||
|
|
Loading…
Reference in New Issue