mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 09:03:57 -03:00
AP_HAL_PX4: fix off-by-one error in RCOutput channel sending
This commit is contained in:
parent
4c3ee76900
commit
e0457f21de
@ -70,8 +70,8 @@ void PX4RCOutput::write(uint8_t ch, uint16_t period_us)
|
|||||||
if (ch >= PX4_NUM_OUTPUT_CHANNELS) {
|
if (ch >= PX4_NUM_OUTPUT_CHANNELS) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
if (ch > _max_channel) {
|
if (ch >= _max_channel) {
|
||||||
_max_channel = ch;
|
_max_channel = ch + 1;
|
||||||
}
|
}
|
||||||
if (period_us != _period[ch]) {
|
if (period_us != _period[ch]) {
|
||||||
_period[ch] = period_us;
|
_period[ch] = period_us;
|
||||||
|
Loading…
Reference in New Issue
Block a user