mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_Linux: fixed get_baud_rate()
This commit is contained in:
parent
80cd126f99
commit
65f7257601
|
@ -56,6 +56,8 @@ 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; }
|
||||||
|
|
||||||
private:
|
private:
|
||||||
AP_HAL::OwnPtr<SerialDevice> _device;
|
AP_HAL::OwnPtr<SerialDevice> _device;
|
||||||
bool _console;
|
bool _console;
|
||||||
|
|
Loading…
Reference in New Issue