AP_HAL_Linux: fix SPIUARTDriver to work with GPS autodetection

GPS auto-detection requires get_baud_rate to return non-zero.  The SPIUARTDriver was returning 0.
This commit is contained in:
Peter Barker 2024-05-07 11:42:24 +10:00 committed by Andrew Tridgell
parent 693151edcd
commit 599ff17f34
3 changed files with 9 additions and 1 deletions

View File

@ -69,14 +69,17 @@ void SPIUARTDriver::_begin(uint32_t b, uint16_t rxS, uint16_t txS)
* it's sage to update speed * it's sage to update speed
*/ */
_dev->set_speed(AP_HAL::Device::SPEED_HIGH); _dev->set_speed(AP_HAL::Device::SPEED_HIGH);
high_speed_set = true;
debug("Set higher SPI-frequency"); debug("Set higher SPI-frequency");
} else { } else {
_dev->set_speed(AP_HAL::Device::SPEED_LOW); _dev->set_speed(AP_HAL::Device::SPEED_LOW);
high_speed_set = false;
debug("Set lower SPI-frequency"); debug("Set lower SPI-frequency");
} }
break; break;
default: default:
_dev->set_speed(AP_HAL::Device::SPEED_LOW); _dev->set_speed(AP_HAL::Device::SPEED_LOW);
high_speed_set = false;
debug("Set lower SPI-frequency"); debug("Set lower SPI-frequency");
debug("%s: wrong baudrate (%u) for SPI-driven device. setting default speed", __func__, b); debug("%s: wrong baudrate (%u) for SPI-driven device. setting default speed", __func__, b);
break; break;

View File

@ -11,6 +11,9 @@ public:
SPIUARTDriver(); SPIUARTDriver();
void _begin(uint32_t b, uint16_t rxS, uint16_t txS) override; void _begin(uint32_t b, uint16_t rxS, uint16_t txS) override;
void _timer_tick(void) override; void _timer_tick(void) override;
uint32_t get_baud_rate() const override {
return high_speed_set ? 4000000U : 1000000U;
}
protected: protected:
int _write_fd(const uint8_t *buf, uint16_t n) override; int _write_fd(const uint8_t *buf, uint16_t n) override;
@ -23,6 +26,8 @@ protected:
uint32_t _last_update_timestamp; uint32_t _last_update_timestamp;
bool _external; bool _external;
bool high_speed_set;
}; };
} }

View File

@ -56,7 +56,7 @@ public:
uint32_t bw_in_bytes_per_second() const override; 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: private:
AP_HAL::OwnPtr<SerialDevice> _device; AP_HAL::OwnPtr<SerialDevice> _device;