mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-24 16:53:57 -04:00
AP_RCProtocol: add error check for ppm input
This commit is contained in:
parent
7a1f87eb52
commit
9e4ec33277
@ -22,6 +22,11 @@
|
|||||||
*/
|
*/
|
||||||
void AP_RCProtocol_PPMSum::process_pulse(uint32_t width_s0, uint32_t width_s1)
|
void AP_RCProtocol_PPMSum::process_pulse(uint32_t width_s0, uint32_t width_s1)
|
||||||
{
|
{
|
||||||
|
if (width_s0 == 0 || width_s1 == 0) {
|
||||||
|
//invalid data: reset frame
|
||||||
|
ppm_state._channel_counter = -1;
|
||||||
|
return;
|
||||||
|
}
|
||||||
uint32_t width_usec = width_s0 + width_s1;
|
uint32_t width_usec = width_s0 + width_s1;
|
||||||
if (width_usec >= 2700) {
|
if (width_usec >= 2700) {
|
||||||
// a long pulse indicates the end of a frame. Reset the
|
// a long pulse indicates the end of a frame. Reset the
|
||||||
|
Loading…
Reference in New Issue
Block a user