Browse Source

APM_RC_APM1.cpp: Bugfix on mapping of SetFastOutputChannels to ICR reg

* Previously had the ICR register for ch1/2/9 (on timer5) swapped with
  ch3/4/10 (on timer1).
* This bug probably didn't make a difference in operation since
  SetFastOutputChannels is typically only used for copters, where at
  least CH1,2,3,4 would be set to fast all at once.
mission-4.1.18
Pat Hickey 13 years ago
parent
commit
7b3009a238
  1. 4
      libraries/APM_RC/APM_RC_APM1.cpp

4
libraries/APM_RC/APM_RC_APM1.cpp

@ -271,11 +271,11 @@ void APM_RC_APM1::SetFastOutputChannels(uint32_t chmask, uint16_t speed_hz) @@ -271,11 +271,11 @@ void APM_RC_APM1::SetFastOutputChannels(uint32_t chmask, uint16_t speed_hz)
uint16_t icr = _map_speed(speed_hz);
if ((chmask & ( _BV(CH_1) | _BV(CH_2) | _BV(CH_9))) != 0) {
ICR1 = icr;
ICR5 = icr;
}
if ((chmask & ( _BV(CH_3) | _BV(CH_4) | _BV(CH_10))) != 0) {
ICR5 = icr;
ICR1 = icr;
}
#if 0

Loading…
Cancel
Save