mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-25 17:23:56 -04:00
AP_HAL_AVR RCPassthroughTest: write to upper (>8) channels as well.
This commit is contained in:
parent
1f670b4ce2
commit
b2a34800e2
@ -31,11 +31,15 @@ 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) {
|
||||
for (int ch = 0; ch < 8; ch++) {
|
||||
out->write(ch, channels[ch]);
|
||||
/* Upper channels duplicate lower channels*/
|
||||
out->write(ch+8, channels[ch]);
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user