mirror of https://github.com/ArduPilot/ardupilot
HAL_Linux: removed Console driver
This commit is contained in:
parent
21f0086647
commit
b30f652cec
|
@ -15,7 +15,6 @@ namespace Linux {
|
|||
class LinuxAnalogSource;
|
||||
class LinuxAnalogIn;
|
||||
class LinuxStorage;
|
||||
class LinuxConsoleDriver;
|
||||
class LinuxGPIO;
|
||||
class LinuxDigitalSource;
|
||||
class LinuxRCInput;
|
||||
|
|
|
@ -11,7 +11,6 @@
|
|||
#include "SPIDriver.h"
|
||||
#include "AnalogIn.h"
|
||||
#include "Storage.h"
|
||||
#include "Console.h"
|
||||
#include "GPIO.h"
|
||||
#include "RCInput.h"
|
||||
#include "RCOutput.h"
|
||||
|
|
|
@ -1,48 +0,0 @@
|
|||
#include <stdarg.h>
|
||||
#include "Console.h"
|
||||
|
||||
using namespace Linux;
|
||||
|
||||
LinuxConsoleDriver::LinuxConsoleDriver(AP_HAL::BetterStream* delegate) :
|
||||
_d(delegate)
|
||||
{}
|
||||
|
||||
void LinuxConsoleDriver::init(void* machtnichts)
|
||||
{}
|
||||
|
||||
void LinuxConsoleDriver::backend_open()
|
||||
{}
|
||||
|
||||
void LinuxConsoleDriver::backend_close()
|
||||
{}
|
||||
|
||||
size_t LinuxConsoleDriver::backend_read(uint8_t *data, size_t len) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
size_t LinuxConsoleDriver::backend_write(const uint8_t *data, size_t len) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
int16_t LinuxConsoleDriver::available() {
|
||||
return _d->available();
|
||||
}
|
||||
|
||||
int16_t LinuxConsoleDriver::txspace() {
|
||||
return _d->txspace();
|
||||
}
|
||||
|
||||
int16_t LinuxConsoleDriver::read() {
|
||||
return _d->read();
|
||||
}
|
||||
|
||||
size_t LinuxConsoleDriver::write(uint8_t c)
|
||||
{
|
||||
return _d->write(c);
|
||||
}
|
||||
|
||||
size_t LinuxConsoleDriver::write(const uint8_t *buffer, size_t size) {
|
||||
return _d->write(buffer, size);
|
||||
}
|
||||
|
||||
|
|
@ -1,27 +0,0 @@
|
|||
|
||||
#ifndef __AP_HAL_LINUX_CONSOLE_H__
|
||||
#define __AP_HAL_LINUX_CONSOLE_H__
|
||||
|
||||
#include <AP_HAL_Linux.h>
|
||||
|
||||
class Linux::LinuxConsoleDriver : public AP_HAL::ConsoleDriver {
|
||||
public:
|
||||
LinuxConsoleDriver(AP_HAL::BetterStream* delegate);
|
||||
void init(void* machtnichts);
|
||||
void backend_open();
|
||||
void backend_close();
|
||||
size_t backend_read(uint8_t *data, size_t len);
|
||||
size_t backend_write(const uint8_t *data, size_t len);
|
||||
|
||||
int16_t available();
|
||||
int16_t txspace();
|
||||
int16_t read();
|
||||
|
||||
size_t write(uint8_t c);
|
||||
size_t write(const uint8_t *buffer, size_t size);
|
||||
|
||||
private:
|
||||
AP_HAL::BetterStream *_d;
|
||||
};
|
||||
|
||||
#endif // __AP_HAL_LINUX_CONSOLE_H__
|
|
@ -21,7 +21,6 @@ static LinuxI2CDriver i2cDriver(&i2cSemaphore, "/dev/i2c-1");
|
|||
static LinuxSPIDeviceManager spiDeviceManager;
|
||||
static LinuxAnalogIn analogIn;
|
||||
static LinuxStorage storageDriver;
|
||||
static LinuxConsoleDriver consoleDriver(&uartADriver);
|
||||
static LinuxGPIO gpioDriver;
|
||||
static LinuxRCInput rcinDriver;
|
||||
static LinuxRCOutput rcoutDriver;
|
||||
|
@ -37,7 +36,7 @@ HAL_Linux::HAL_Linux() :
|
|||
&spiDeviceManager,
|
||||
&analogIn,
|
||||
&storageDriver,
|
||||
&consoleDriver,
|
||||
&uartADriver,
|
||||
&gpioDriver,
|
||||
&rcinDriver,
|
||||
&rcoutDriver,
|
||||
|
|
Loading…
Reference in New Issue