diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.cpp b/libraries/AP_Motors/AP_MotorsMulticopter.cpp index 154bcaa0fa..86fe5ae346 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.cpp +++ b/libraries/AP_Motors/AP_MotorsMulticopter.cpp @@ -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), diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.h b/libraries/AP_Motors/AP_MotorsMulticopter.h index 59e02f4b0e..4cc9c09ce5 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.h +++ b/libraries/AP_Motors/AP_MotorsMulticopter.h @@ -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