RC_Channel: cope with SERVO_RNG_ENABLE changing while booted

this prevents a one second throttle up on scaled ESCs when
enabling/disabling the servo output mapping
This commit is contained in:
Andrew Tridgell 2016-10-12 16:02:58 +11:00
parent be1109174e
commit 992bf2368e
2 changed files with 11 additions and 0 deletions

View File

@ -216,6 +216,13 @@ uint16_t SRV_Channels::remap_pwm(uint8_t i, uint16_t pwm) const
*/
void SRV_Channels::remap_servo_output(void)
{
// cope with SERVO_RNG_ENABLE being changed at runtime. If we
// don't change the ESC scaling immediately then some ESCs will
// fire up for one second
if (last_enable != enable && esc_cal_chan != -1) {
last_enable = enable;
set_esc_scaling(esc_cal_chan);
}
if (!enable) {
return;
}
@ -254,6 +261,7 @@ void SRV_Channels::set_trim(void)
void SRV_Channels::set_esc_scaling(uint8_t chnum)
{
esc_cal_chan = chnum;
if (!enable || chnum >= NUM_SERVO_RANGE_CHANNELS) {
const RC_Channel *ch = RC_Channel::rc_channel(chnum);
hal.rcout->set_esc_scaling(ch->get_radio_min(), ch->get_radio_max());

View File

@ -43,6 +43,9 @@ public:
private:
AP_Int8 enable;
int8_t esc_cal_chan;
bool last_enable;
// PWM values for min/max and trim
AP_Int16 servo_min[NUM_SERVO_RANGE_CHANNELS];
AP_Int16 servo_max[NUM_SERVO_RANGE_CHANNELS];