mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
PPMEncoder - bug fix from previous commit
This commit is contained in:
parent
4f9b787e04
commit
bcd142ec0b
@ -804,7 +804,7 @@ ISR( PPM_INT_VECTOR, ISR_NOBLOCK )
|
|||||||
if( ppm_timeout[ ppm_out_channel ] > PPM_TIMEOUT_VALUE )
|
if( ppm_timeout[ ppm_out_channel ] > PPM_TIMEOUT_VALUE )
|
||||||
{
|
{
|
||||||
// Channel 1-4?
|
// Channel 1-4?
|
||||||
if( ppm_out_channel & 7 )
|
if( ppm_out_channel < 8 )
|
||||||
{
|
{
|
||||||
// Channel 1-4 - Use fail-safe value
|
// Channel 1-4 - Use fail-safe value
|
||||||
cli();
|
cli();
|
||||||
|
Loading…
Reference in New Issue
Block a user