mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_HAL_SITL: fixed get_baud_rate()
This commit is contained in:
parent
b4160ddd93
commit
973e70ab3c
@ -65,6 +65,8 @@ public:
|
||||
*/
|
||||
uint64_t receive_time_constraint_us(uint16_t nbytes) override;
|
||||
|
||||
uint32_t get_baud_rate() const override { return _uart_baudrate; }
|
||||
|
||||
private:
|
||||
|
||||
int _fd;
|
||||
|
Loading…
Reference in New Issue
Block a user