mirror of https://github.com/ArduPilot/ardupilot
RC_Channel: fixed output for k_motor*
This commit is contained in:
parent
1b682e3c8f
commit
b6155d2cb6
|
@ -35,6 +35,9 @@ RC_Channel_aux::output_ch(void)
|
||||||
case k_manual: // manual
|
case k_manual: // manual
|
||||||
radio_out = radio_in;
|
radio_out = radio_in;
|
||||||
break;
|
break;
|
||||||
|
case k_motor1 ... k_motor8:
|
||||||
|
// handled by AP_Motors::rc_write()
|
||||||
|
return;
|
||||||
}
|
}
|
||||||
hal.rcout->write(_ch_out, radio_out);
|
hal.rcout->write(_ch_out, radio_out);
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue