mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_HAL_ESP32: fixed get_baud_rate()
This commit is contained in:
parent
6d12f49a90
commit
ad93f871d4
@ -71,6 +71,9 @@ public:
|
|||||||
A return value of zero means the HAL does not support this API */
|
A return value of zero means the HAL does not support this API */
|
||||||
|
|
||||||
uint64_t receive_time_constraint_us(uint16_t nbytes) override;
|
uint64_t receive_time_constraint_us(uint16_t nbytes) override;
|
||||||
|
|
||||||
|
uint32_t get_baud_rate() const override { return _baudrate; }
|
||||||
|
|
||||||
private:
|
private:
|
||||||
bool _initialized;
|
bool _initialized;
|
||||||
const size_t TX_BUF_SIZE = 1024;
|
const size_t TX_BUF_SIZE = 1024;
|
||||||
|
Loading…
Reference in New Issue
Block a user