Skip to content

Commit

Permalink
AP_HAL: UARTDriver, add baudrate
Browse files Browse the repository at this point in the history
  • Loading branch information
olliw42 committed Oct 5, 2024
1 parent be1c87f commit 9c000a6
Showing 1 changed file with 3 additions and 4 deletions.
7 changes: 3 additions & 4 deletions libraries/AP_HAL/UARTDriver.h
Original file line number Diff line number Diff line change
Expand Up @@ -148,11 +148,9 @@ class AP_HAL::UARTDriver : public AP_HAL::BetterStream {
*/
virtual uint64_t receive_time_constraint_us(uint16_t nbytes);

virtual uint32_t bw_in_bytes_per_second() const {
return 5760;
}
virtual uint32_t bw_in_bytes_per_second() const { return (baudrate >= 10) ? baudrate/10 : 5760; } // ensure it is not 0, as it may be used in a devide

virtual uint32_t get_baud_rate() const { return 0; }
virtual uint32_t get_baud_rate() const { return baudrate; }

/*
return true if this UART has DMA enabled on both RX and TX
Expand Down Expand Up @@ -219,6 +217,7 @@ class AP_HAL::UARTDriver : public AP_HAL::BetterStream {
uint32_t lock_write_key;
uint32_t lock_read_key;

uint32_t baudrate;
uint8_t parity;

/*
Expand Down

0 comments on commit 9c000a6

Please sign in to comment.