From 9354aca07da3a2bd131a315e6c30e51a2a9142c9 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 2 Nov 2018 21:13:21 +1100 Subject: [PATCH] AP_RCProtocol: removed some unnecessary millis calls --- libraries/AP_RCProtocol/AP_RCProtocol.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_RCProtocol/AP_RCProtocol.cpp b/libraries/AP_RCProtocol/AP_RCProtocol.cpp index ddb6d889c6..7ad713ef5c 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol.cpp +++ b/libraries/AP_RCProtocol/AP_RCProtocol.cpp @@ -50,7 +50,7 @@ void AP_RCProtocol::process_pulse(uint32_t width_s0, uint32_t width_s1) backend[_detected_protocol]->process_pulse(width_s0, width_s1); if (backend[_detected_protocol]->new_input()) { _new_input = true; - _last_input_ms = AP_HAL::millis(); + _last_input_ms = now; } return; } @@ -68,7 +68,7 @@ void AP_RCProtocol::process_pulse(uint32_t width_s0, uint32_t width_s1) if (backend[i]->new_input()) { _new_input = true; _detected_protocol = (enum AP_RCProtocol::rcprotocol_t)i; - _last_input_ms = AP_HAL::millis(); + _last_input_ms = now; _detected_with_bytes = false; } } @@ -87,7 +87,7 @@ void AP_RCProtocol::process_byte(uint8_t byte, uint32_t baudrate) backend[_detected_protocol]->process_byte(byte, baudrate); if (backend[_detected_protocol]->new_input()) { _new_input = true; - _last_input_ms = AP_HAL::millis(); + _last_input_ms = now; } return; } @@ -99,7 +99,7 @@ void AP_RCProtocol::process_byte(uint8_t byte, uint32_t baudrate) if (backend[i]->new_input()) { _new_input = true; _detected_protocol = (enum AP_RCProtocol::rcprotocol_t)i; - _last_input_ms = AP_HAL::millis(); + _last_input_ms = now; _detected_with_bytes = true; } }