AP_SerialManager: RegisteredPort, add bytes_per_second/baudrate methods

This commit is contained in:
olliw42 2024-10-05 10:48:44 +02:00 committed by Andrew Tridgell
parent e9e7eba799
commit 4616fec1be
1 changed files with 2 additions and 0 deletions

View File

@ -175,6 +175,8 @@ public:
*/
class RegisteredPort : public AP_HAL::UARTDriver {
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;
UARTState state;
};