diff --git a/libraries/AP_HAL_PX4/RCInput.cpp b/libraries/AP_HAL_PX4/RCInput.cpp index 81895c851f..e7c0467a76 100644 --- a/libraries/AP_HAL_PX4/RCInput.cpp +++ b/libraries/AP_HAL_PX4/RCInput.cpp @@ -23,7 +23,7 @@ void PX4RCInput::init(void* unused) uint8_t PX4RCInput::valid_channels() { pthread_mutex_lock(&rcin_mutex); - bool valid = _rcin.timestamp != _last_read || _override_valid; + bool valid = _rcin.timestamp_last_signal != _last_read || _override_valid; pthread_mutex_unlock(&rcin_mutex); return valid; } @@ -34,7 +34,7 @@ uint16_t PX4RCInput::read(uint8_t ch) return 0; } pthread_mutex_lock(&rcin_mutex); - _last_read = _rcin.timestamp; + _last_read = _rcin.timestamp_last_signal; _override_valid = false; if (_override[ch]) { uint16_t v = _override[ch]; diff --git a/libraries/AP_HAL_PX4/Util.cpp b/libraries/AP_HAL_PX4/Util.cpp index f32627c099..eefb40f589 100644 --- a/libraries/AP_HAL_PX4/Util.cpp +++ b/libraries/AP_HAL_PX4/Util.cpp @@ -11,7 +11,7 @@ #include "UARTDriver.h" #include #include -#include +#include extern const AP_HAL::HAL& hal; @@ -105,7 +105,7 @@ bool PX4Util::get_system_id(char buf[40]) { uint8_t serialid[12]; memset(serialid, 0, sizeof(serialid)); - val_read(serialid, (const void *)UDID_START, sizeof(serialid)); + get_board_serial(serialid); #ifdef CONFIG_ARCH_BOARD_PX4FMU_V1 const char *board_type = "PX4v1"; #else