mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_SITL: fixed get_baud_rate()
This commit is contained in:
parent
65f7257601
commit
aa1871a3f4
|
@ -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