2012-08-20 15:37:46 -03:00
|
|
|
|
|
|
|
#ifndef __AP_HAL_UART_DRIVER_H__
|
|
|
|
#define __AP_HAL_UART_DRIVER_H__
|
|
|
|
|
|
|
|
#include <stdint.h>
|
|
|
|
|
2015-10-22 14:00:28 -03:00
|
|
|
#include <AP_Common/AP_Common.h>
|
|
|
|
|
2012-08-20 15:37:46 -03:00
|
|
|
#include "AP_HAL_Namespace.h"
|
2012-08-20 20:54:01 -03:00
|
|
|
#include "utility/BetterStream.h"
|
2012-08-20 15:37:46 -03:00
|
|
|
|
|
|
|
/* Pure virtual UARTDriver class */
|
2012-08-20 20:54:01 -03:00
|
|
|
class AP_HAL::UARTDriver : public AP_HAL::BetterStream {
|
2012-08-20 15:37:46 -03:00
|
|
|
public:
|
|
|
|
UARTDriver() {}
|
2012-12-06 14:55:13 -04:00
|
|
|
virtual void begin(uint32_t baud) = 0;
|
2012-08-23 21:22:46 -03:00
|
|
|
/// Extended port open method
|
|
|
|
///
|
|
|
|
/// Allows for both opening with specified buffer sizes, and re-opening
|
|
|
|
/// to adjust a subset of the port's settings.
|
|
|
|
///
|
|
|
|
/// @note Buffer sizes greater than ::_max_buffer_size will be rounded
|
|
|
|
/// down.
|
|
|
|
///
|
|
|
|
/// @param baud Selects the speed that the port will be
|
|
|
|
/// configured to. If zero, the port speed is left
|
|
|
|
/// unchanged.
|
|
|
|
/// @param rxSpace Sets the receive buffer size for the port. If zero
|
|
|
|
/// then the buffer size is left unchanged if the port
|
|
|
|
/// is open, or set to ::_default_rx_buffer_size if it is
|
|
|
|
/// currently closed.
|
|
|
|
/// @param txSpace Sets the transmit buffer size for the port. If zero
|
|
|
|
/// then the buffer size is left unchanged if the port
|
|
|
|
/// is open, or set to ::_default_tx_buffer_size if it
|
|
|
|
/// is currently closed.
|
|
|
|
///
|
2012-12-06 14:55:13 -04:00
|
|
|
virtual void begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace) = 0;
|
2012-08-21 18:11:24 -03:00
|
|
|
virtual void end() = 0;
|
|
|
|
virtual void flush() = 0;
|
|
|
|
virtual bool is_initialized() = 0;
|
|
|
|
virtual void set_blocking_writes(bool blocking) = 0;
|
|
|
|
virtual bool tx_pending() = 0;
|
2014-02-10 20:22:08 -04:00
|
|
|
|
|
|
|
enum flow_control {
|
|
|
|
FLOW_CONTROL_DISABLE=0, FLOW_CONTROL_ENABLE=1, FLOW_CONTROL_AUTO=2
|
|
|
|
};
|
2014-02-11 19:51:58 -04:00
|
|
|
virtual void set_flow_control(enum flow_control flow_control_setting) {};
|
2014-02-13 22:15:24 -04:00
|
|
|
virtual enum flow_control get_flow_control(void) { return FLOW_CONTROL_DISABLE; };
|
2013-09-21 23:20:59 -03:00
|
|
|
|
|
|
|
/* Implementations of BetterStream virtual methods. These are
|
|
|
|
* provided by AP_HAL to ensure consistency between ports to
|
|
|
|
* different boards
|
|
|
|
*/
|
2015-11-10 13:05:19 -04:00
|
|
|
void printf(const char *s, ...) FMT_PRINTF(2, 3);
|
2013-09-21 23:20:59 -03:00
|
|
|
void vprintf(const char *s, va_list ap);
|
2012-08-20 20:54:01 -03:00
|
|
|
};
|
|
|
|
|
2012-08-20 15:37:46 -03:00
|
|
|
#endif // __AP_HAL_UART_DRIVER_H__
|
|
|
|
|