mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AP_HAL_AVR: RCOutput_APM2, bugfix to get_freq on CH_10 and CH_11
This commit is contained in:
parent
875e928628
commit
ad64fd2924
@ -91,9 +91,11 @@ uint16_t APM2RCOutput::get_freq(uint8_t ch) {
|
||||
case CH_8:
|
||||
icr = ICR3;
|
||||
break;
|
||||
/* CH_10 and CH_11 share TIMER5 with input capture.
|
||||
* The period is specified in OCR5A rater than the ICR. */
|
||||
case CH_10:
|
||||
case CH_11:
|
||||
icr = ICR5;
|
||||
icr = OCR5A;
|
||||
break;
|
||||
default:
|
||||
return 0;
|
||||
|
Loading…
Reference in New Issue
Block a user