AP_HAL_FLYMAPLE: remove the only user of multiwrite

This is the only place where this variant of RCOutput::write() is
called. Remove it so to use the common interface. It can be added back
later when there's support for asynchronous write.
This commit is contained in:
Lucas De Marchi 2015-08-24 19:11:36 -03:00 committed by Randy Mackay
parent 26329c5a03
commit a5cc0be531

View File

@ -35,12 +35,6 @@ void individualread(AP_HAL::RCInput* in, uint16_t* channels) {
} }
void multiwrite(AP_HAL::RCOutput* out, uint16_t* channels) {
out->write(0, channels, 8);
/* Upper channels duplicate lower channels*/
out->write(8, channels, 8);
}
void individualwrite(AP_HAL::RCOutput* out, uint16_t* channels) { void individualwrite(AP_HAL::RCOutput* out, uint16_t* channels) {
for (int ch = 0; ch < 8; ch++) { for (int ch = 0; ch < 8; ch++) {
out->write(ch, channels[ch]); out->write(ch, channels[ch]);
@ -64,12 +58,7 @@ void loop (void) {
if (ctr > 1000) ctr = 0; if (ctr > 1000) ctr = 0;
} }
/* Cycle between individual output and multichannel output */ individualwrite(hal.rcout, channels);
if (ctr % 500 < 250) {
multiwrite(hal.rcout, channels);
} else {
individualwrite(hal.rcout, channels);
}
// hal.gpio->write(13, 0); // hal.gpio->write(13, 0);
hal.scheduler->delay(4); hal.scheduler->delay(4);