mirror of https://github.com/ArduPilot/ardupilot
AP_SerialManager: RegisteredPort, add bytes_per_second/baudrate methods
This commit is contained in:
parent
e9e7eba799
commit
4616fec1be
|
@ -175,6 +175,8 @@ public:
|
||||||
*/
|
*/
|
||||||
class RegisteredPort : public AP_HAL::UARTDriver {
|
class RegisteredPort : public AP_HAL::UARTDriver {
|
||||||
public:
|
public:
|
||||||
|
uint32_t bw_in_bytes_per_second() const override { return state.baudrate()/10; }
|
||||||
|
uint32_t get_baud_rate() const override { return state.baudrate(); }
|
||||||
RegisteredPort *next;
|
RegisteredPort *next;
|
||||||
UARTState state;
|
UARTState state;
|
||||||
};
|
};
|
||||||
|
|
Loading…
Reference in New Issue