mirror of https://github.com/ArduPilot/ardupilot
AP_HAL: add support for usb passthrough with baud changes
This commit is contained in:
parent
d1b0438412
commit
4b8b0f834d
|
@ -17,6 +17,8 @@ public:
|
|||
|
||||
// begin() implicitly clears rx/tx buffers, even if the port was already open (unless the UART is the console UART)
|
||||
virtual void begin(uint32_t baud) = 0;
|
||||
virtual void begin_locked(uint32_t baud, uint32_t key) { begin(baud); }
|
||||
|
||||
/// Extended port open method
|
||||
///
|
||||
/// Allows for both opening with specified buffer sizes, and re-opening
|
||||
|
@ -137,4 +139,7 @@ public:
|
|||
*/
|
||||
virtual bool set_RTS_pin(bool high) { return false; };
|
||||
virtual bool set_CTS_pin(bool high) { return false; };
|
||||
|
||||
// return true requested baud on USB port
|
||||
virtual uint32_t get_usb_baud(void) const { return 0; }
|
||||
};
|
||||
|
|
|
@ -100,11 +100,6 @@ public:
|
|||
*/
|
||||
virtual uint64_t get_hw_rtc() const;
|
||||
|
||||
/*
|
||||
get the requested usb baudrate - 0 = none
|
||||
*/
|
||||
virtual uint32_t get_usb_baud(uint16_t endpoint_id) { return 0; }
|
||||
|
||||
enum class FlashBootloader {
|
||||
OK=0,
|
||||
NO_CHANGE=1,
|
||||
|
|
Loading…
Reference in New Issue