diff --git a/libraries/AP_HAL_Linux/SPIUARTDriver.cpp b/libraries/AP_HAL_Linux/SPIUARTDriver.cpp index e6a266b564135b..476ab6655a578f 100644 --- a/libraries/AP_HAL_Linux/SPIUARTDriver.cpp +++ b/libraries/AP_HAL_Linux/SPIUARTDriver.cpp @@ -69,14 +69,17 @@ void SPIUARTDriver::_begin(uint32_t b, uint16_t rxS, uint16_t txS) * it's sage to update speed */ _dev->set_speed(AP_HAL::Device::SPEED_HIGH); + high_speed_set = true; debug("Set higher SPI-frequency"); } else { _dev->set_speed(AP_HAL::Device::SPEED_LOW); + high_speed_set = false; debug("Set lower SPI-frequency"); } break; default: _dev->set_speed(AP_HAL::Device::SPEED_LOW); + high_speed_set = false; debug("Set lower SPI-frequency"); debug("%s: wrong baudrate (%u) for SPI-driven device. setting default speed", __func__, b); break; diff --git a/libraries/AP_HAL_Linux/SPIUARTDriver.h b/libraries/AP_HAL_Linux/SPIUARTDriver.h index 05be43b9ecce0c..07e451d243bc48 100644 --- a/libraries/AP_HAL_Linux/SPIUARTDriver.h +++ b/libraries/AP_HAL_Linux/SPIUARTDriver.h @@ -11,6 +11,9 @@ class SPIUARTDriver : public UARTDriver { SPIUARTDriver(); void _begin(uint32_t b, uint16_t rxS, uint16_t txS) override; void _timer_tick(void) override; + uint32_t get_baud_rate() const override { + return high_speed_set ? 4000000U : 1000000U; + } protected: int _write_fd(const uint8_t *buf, uint16_t n) override; @@ -23,6 +26,8 @@ class SPIUARTDriver : public UARTDriver { uint32_t _last_update_timestamp; bool _external; + + bool high_speed_set; }; } diff --git a/libraries/AP_HAL_Linux/UARTDriver.h b/libraries/AP_HAL_Linux/UARTDriver.h index ec47114cc6ee3d..02a1afba7b88e9 100644 --- a/libraries/AP_HAL_Linux/UARTDriver.h +++ b/libraries/AP_HAL_Linux/UARTDriver.h @@ -56,7 +56,7 @@ class UARTDriver : public AP_HAL::UARTDriver { uint32_t bw_in_bytes_per_second() const override; - uint32_t get_baud_rate() const override { return _baudrate; } + virtual uint32_t get_baud_rate() const override { return _baudrate; } private: AP_HAL::OwnPtr _device;