mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_AVR: fixed multi-channel RC output
This commit is contained in:
parent
9058949558
commit
e852d6300f
|
@ -191,7 +191,7 @@ void APM1RCOutput::write(uint8_t ch, uint16_t period_us) {
|
|||
}
|
||||
|
||||
void APM1RCOutput::write(uint8_t ch, uint16_t* period_us, uint8_t len) {
|
||||
for (int i = 0; i < ch; i++) {
|
||||
for (int i = 0; i < len; i++) {
|
||||
write(i + ch, period_us[i]);
|
||||
}
|
||||
}
|
||||
|
|
|
@ -183,7 +183,7 @@ void APM2RCOutput::write(uint8_t ch, uint16_t period_us) {
|
|||
}
|
||||
|
||||
void APM2RCOutput::write(uint8_t ch, uint16_t* period_us, uint8_t len) {
|
||||
for (int i = 0; i < ch; i++) {
|
||||
for (int i = 0; i < len; i++) {
|
||||
write(i + ch, period_us[i]);
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue