AP_Motors: tie esc scaling with set_throttle_range()

We need to update the esc scaling from inside the Motors library, that
has access to the MOT_PWM_[MIN|MAX] values. Otherwise even though the
AP_Motors library honors the value for calculations, the RCOutput
drivers that need the scaling to set the real HW scaling will not work.
Right now it scales the value using the throttle_channel's min/max, even
though AP_Motors may be passing values in other range.
This commit is contained in:
Lucas De Marchi 2017-02-09 19:14:28 -08:00 committed by Andrew Tridgell
parent e1eda3066c
commit ade1876318

View File

@ -394,10 +394,14 @@ int16_t AP_MotorsMulticopter::get_pwm_output_max() const
void AP_MotorsMulticopter::set_throttle_range(int16_t radio_min, int16_t radio_max) void AP_MotorsMulticopter::set_throttle_range(int16_t radio_min, int16_t radio_max)
{ {
// sanity check // sanity check
if ((radio_max > radio_min)) { if (radio_max <= radio_min) {
_throttle_radio_min = radio_min; return;
_throttle_radio_max = radio_max;
} }
_throttle_radio_min = radio_min;
_throttle_radio_max = radio_max;
hal.rcout->set_esc_scaling(get_pwm_output_min(), get_pwm_output_max());
} }
// update the throttle input filter. should be called at 100hz // update the throttle input filter. should be called at 100hz