ardupilot/libraries/AP_HAL_Empty/UARTDriver.h

30 lines
916 B
C
Raw Normal View History

#pragma once
#include "AP_HAL_Empty.h"
class Empty::UARTDriver : public AP_HAL::UARTDriver {
public:
UARTDriver();
/* Empty implementations of UARTDriver virtual methods */
void begin(uint32_t b) override;
void begin(uint32_t b, uint16_t rxS, uint16_t txS) override;
void end() override;
void flush() override;
bool is_initialized() override;
void set_blocking_writes(bool blocking) override;
bool tx_pending() override;
/* Empty implementations of Stream virtual methods */
uint32_t available() override;
uint32_t txspace() override;
int16_t read() override;
bool discard_input() override;
/* Empty implementations of Print virtual methods */
size_t write(uint8_t c) override;
size_t write(const uint8_t *buffer, size_t size) override;
2021-06-05 00:50:28 -03:00
// request information on uart I/O for one uart
void uart_info(ExpandingString &str) override;
};